mirror of
https://github.com/CopterExpress/clover.git
synced 2026-06-01 15:39:32 +00:00
Compare commits
6 Commits
bullseye
...
terrain-fr
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
aa89077c23 | ||
|
|
4e9d8a64d0 | ||
|
|
94171d51ac | ||
|
|
0d45b6cb7f | ||
|
|
eb448ae0e7 | ||
|
|
d61760a718 |
@@ -1,735 +0,0 @@
|
||||
catkin:
|
||||
debian:
|
||||
bullseye: [ros-noetic-catkin]
|
||||
genmsg:
|
||||
debian:
|
||||
bullseye: [ros-noetic-genmsg]
|
||||
gencpp:
|
||||
debian:
|
||||
bullseye: [ros-noetic-gencpp]
|
||||
geneus:
|
||||
debian:
|
||||
bullseye: [ros-noetic-geneus]
|
||||
genlisp:
|
||||
debian:
|
||||
bullseye: [ros-noetic-genlisp]
|
||||
gennodejs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-gennodejs]
|
||||
genpy:
|
||||
debian:
|
||||
bullseye: [ros-noetic-genpy]
|
||||
bond_core:
|
||||
debian:
|
||||
bullseye: [ros-noetic-bond-core]
|
||||
cmake_modules:
|
||||
debian:
|
||||
bullseye: [ros-noetic-cmake-modules]
|
||||
class_loader:
|
||||
debian:
|
||||
bullseye: [ros-noetic-class-loader]
|
||||
common_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-common-msgs]
|
||||
common_tutorials:
|
||||
debian:
|
||||
bullseye: [ros-noetic-common-tutorials]
|
||||
cpp_common:
|
||||
debian:
|
||||
bullseye: [ros-noetic-cpp-common]
|
||||
desktop:
|
||||
debian:
|
||||
bullseye: [ros-noetic-desktop]
|
||||
diagnostics:
|
||||
debian:
|
||||
bullseye: [ros-noetic-diagnostics]
|
||||
executive_smach:
|
||||
debian:
|
||||
bullseye: [ros-noetic-executive-smach]
|
||||
geometry:
|
||||
debian:
|
||||
bullseye: [ros-noetic-geometry]
|
||||
geometry_tutorials:
|
||||
debian:
|
||||
bullseye: [ros-noetic-geometry-tutorials]
|
||||
gl_dependency:
|
||||
debian:
|
||||
bullseye: [ros-noetic-gl-dependency]
|
||||
image_common:
|
||||
debian:
|
||||
bullseye: [ros-noetic-image-common]
|
||||
image_pipeline:
|
||||
debian:
|
||||
bullseye: [ros-noetic-image-pipeline]
|
||||
image_transport_plugins:
|
||||
debian:
|
||||
bullseye: [ros-noetic-image-transport-plugins]
|
||||
laser_pipeline:
|
||||
debian:
|
||||
bullseye: [ros-noetic-laser-pipeline]
|
||||
mavlink:
|
||||
debian:
|
||||
bullseye: [ros-noetic-mavlink]
|
||||
media_export:
|
||||
debian:
|
||||
bullseye: [ros-noetic-media-export]
|
||||
message_generation:
|
||||
debian:
|
||||
bullseye: [ros-noetic-message-generation]
|
||||
message_runtime:
|
||||
debian:
|
||||
bullseye: [ros-noetic-message-runtime]
|
||||
mk:
|
||||
debian:
|
||||
bullseye: [ros-noetic-mk]
|
||||
nodelet_core:
|
||||
debian:
|
||||
bullseye: [ros-noetic-nodelet-core]
|
||||
orocos_kdl:
|
||||
debian:
|
||||
bullseye: [ros-noetic-orocos-kdl]
|
||||
perception:
|
||||
debian:
|
||||
bullseye: [ros-noetic-perception]
|
||||
perception_pcl:
|
||||
debian:
|
||||
bullseye: [ros-noetic-perception-pcl]
|
||||
python_orocos_kdl:
|
||||
debian:
|
||||
bullseye: [ros-noetic-python-orocos-kdl]
|
||||
qt_dotgraph:
|
||||
debian:
|
||||
bullseye: [ros-noetic-qt-dotgraph]
|
||||
qt_gui:
|
||||
debian:
|
||||
bullseye: [ros-noetic-qt-gui]
|
||||
qt_gui_py_common:
|
||||
debian:
|
||||
bullseye: [ros-noetic-qt-gui-py-common]
|
||||
qwt_dependency:
|
||||
debian:
|
||||
bullseye: [ros-noetic-qwt-dependency]
|
||||
robot:
|
||||
debian:
|
||||
bullseye: [ros-noetic-robot]
|
||||
ros:
|
||||
debian:
|
||||
bullseye: [ros-noetic-ros]
|
||||
ros_base:
|
||||
debian:
|
||||
bullseye: [ros-noetic-ros-base]
|
||||
ros_comm:
|
||||
debian:
|
||||
bullseye: [ros-noetic-ros-comm]
|
||||
ros_core:
|
||||
debian:
|
||||
bullseye: [ros-noetic-ros-core]
|
||||
ros_environment:
|
||||
debian:
|
||||
bullseye: [ros-noetic-ros-environment]
|
||||
ros_tutorials:
|
||||
debian:
|
||||
bullseye: [ros-noetic-ros-tutorials]
|
||||
rosapi:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosapi]
|
||||
rosbag_migration_rule:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosbag-migration-rule]
|
||||
rosbash:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosbash]
|
||||
rosboost_cfg:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosboost-cfg]
|
||||
rosbridge_server:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosbridge-server]
|
||||
rosbridge_suite:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosbridge-suite]
|
||||
rosbuild:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosbuild]
|
||||
rosclean:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosclean]
|
||||
roscpp_core:
|
||||
debian:
|
||||
bullseye: [ros-noetic-roscpp-core]
|
||||
roscpp_traits:
|
||||
debian:
|
||||
bullseye: [ros-noetic-roscpp-traits]
|
||||
roscreate:
|
||||
debian:
|
||||
bullseye: [ros-noetic-roscreate]
|
||||
rosgraph:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosgraph]
|
||||
roslang:
|
||||
debian:
|
||||
bullseye: [ros-noetic-roslang]
|
||||
roslint:
|
||||
debian:
|
||||
bullseye: [ros-noetic-roslint]
|
||||
roslisp:
|
||||
debian:
|
||||
bullseye: [ros-noetic-roslisp]
|
||||
rosmake:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosmake]
|
||||
rosmaster:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosmaster]
|
||||
rospack:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rospack]
|
||||
roslib:
|
||||
debian:
|
||||
bullseye: [ros-noetic-roslib]
|
||||
rosparam:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosparam]
|
||||
rospy:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rospy]
|
||||
rosserial:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosserial]
|
||||
rosserial_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosserial-msgs]
|
||||
rosserial_python:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosserial-python]
|
||||
rosservice:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosservice]
|
||||
rostime:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rostime]
|
||||
roscpp_serialization:
|
||||
debian:
|
||||
bullseye: [ros-noetic-roscpp-serialization]
|
||||
python_qt_binding:
|
||||
debian:
|
||||
bullseye: [ros-noetic-python-qt-binding]
|
||||
roslaunch:
|
||||
debian:
|
||||
bullseye: [ros-noetic-roslaunch]
|
||||
rosunit:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosunit]
|
||||
angles:
|
||||
debian:
|
||||
bullseye: [ros-noetic-angles]
|
||||
libmavconn:
|
||||
debian:
|
||||
bullseye: [ros-noetic-libmavconn]
|
||||
rosconsole:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosconsole]
|
||||
pluginlib:
|
||||
debian:
|
||||
bullseye: [ros-noetic-pluginlib]
|
||||
qt_gui_cpp:
|
||||
debian:
|
||||
bullseye: [ros-noetic-qt-gui-cpp]
|
||||
resource_retriever:
|
||||
debian:
|
||||
bullseye: [ros-noetic-resource-retriever]
|
||||
rosconsole_bridge:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosconsole-bridge]
|
||||
roslz4:
|
||||
debian:
|
||||
bullseye: [ros-noetic-roslz4]
|
||||
rosserial_client:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosserial-client]
|
||||
rostest:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rostest]
|
||||
rqt_action:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-action]
|
||||
rqt_bag:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-bag]
|
||||
rqt_bag_plugins:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-bag-plugins]
|
||||
rqt_common_plugins:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-common-plugins]
|
||||
rqt_console:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-console]
|
||||
rqt_dep:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-dep]
|
||||
rqt_graph:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-graph]
|
||||
rqt_gui:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-gui]
|
||||
rqt_logger_level:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-logger-level]
|
||||
rqt_moveit:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-moveit]
|
||||
rqt_msg:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-msg]
|
||||
rqt_nav_view:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-nav-view]
|
||||
rqt_plot:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-plot]
|
||||
rqt_pose_view:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-pose-view]
|
||||
rqt_publisher:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-publisher]
|
||||
rqt_py_console:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-py-console]
|
||||
rqt_reconfigure:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-reconfigure]
|
||||
rqt_robot_dashboard:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-robot-dashboard]
|
||||
rqt_robot_monitor:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-robot-monitor]
|
||||
rqt_robot_plugins:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-robot-plugins]
|
||||
rqt_robot_steering:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-robot-steering]
|
||||
rqt_runtime_monitor:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-runtime-monitor]
|
||||
rqt_service_caller:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-service-caller]
|
||||
rqt_shell:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-shell]
|
||||
rqt_srv:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-srv]
|
||||
rqt_tf_tree:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-tf-tree]
|
||||
rqt_top:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-top]
|
||||
rqt_topic:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-topic]
|
||||
rqt_web:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-web]
|
||||
smach:
|
||||
debian:
|
||||
bullseye: [ros-noetic-smach]
|
||||
smclib:
|
||||
debian:
|
||||
bullseye: [ros-noetic-smclib]
|
||||
std_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-std-msgs]
|
||||
actionlib_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-actionlib-msgs]
|
||||
bond:
|
||||
debian:
|
||||
bullseye: [ros-noetic-bond]
|
||||
diagnostic_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-diagnostic-msgs]
|
||||
geometry_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-geometry-msgs]
|
||||
eigen_conversions:
|
||||
debian:
|
||||
bullseye: [ros-noetic-eigen-conversions]
|
||||
kdl_conversions:
|
||||
debian:
|
||||
bullseye: [ros-noetic-kdl-conversions]
|
||||
nav_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-nav-msgs]
|
||||
rosbridge_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosbridge-msgs]
|
||||
rosgraph_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosgraph-msgs]
|
||||
rosmsg:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosmsg]
|
||||
rqt_py_common:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-py-common]
|
||||
shape_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-shape-msgs]
|
||||
smach_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-smach-msgs]
|
||||
std_srvs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-std-srvs]
|
||||
tf2_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-tf2-msgs]
|
||||
tf2:
|
||||
debian:
|
||||
bullseye: [ros-noetic-tf2]
|
||||
tf2_eigen:
|
||||
debian:
|
||||
bullseye: [ros-noetic-tf2-eigen]
|
||||
trajectory_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-trajectory-msgs]
|
||||
control_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-control-msgs]
|
||||
urdf_parser_plugin:
|
||||
debian:
|
||||
bullseye: [ros-noetic-urdf-parser-plugin]
|
||||
urdfdom_py:
|
||||
debian:
|
||||
bullseye: [ros-noetic-urdfdom-py]
|
||||
uuid_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-uuid-msgs]
|
||||
geographic_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-geographic-msgs]
|
||||
vision_opencv:
|
||||
debian:
|
||||
bullseye: [ros-noetic-vision-opencv]
|
||||
visualization_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-visualization-msgs]
|
||||
visualization_tutorials:
|
||||
debian:
|
||||
bullseye: [ros-noetic-visualization-tutorials]
|
||||
viz:
|
||||
debian:
|
||||
bullseye: [ros-noetic-viz]
|
||||
webkit_dependency:
|
||||
debian:
|
||||
bullseye: [ros-noetic-webkit-dependency]
|
||||
xmlrpcpp:
|
||||
debian:
|
||||
bullseye: [ros-noetic-xmlrpcpp]
|
||||
roscpp:
|
||||
debian:
|
||||
bullseye: [ros-noetic-roscpp]
|
||||
bondcpp:
|
||||
debian:
|
||||
bullseye: [ros-noetic-bondcpp]
|
||||
bondpy:
|
||||
debian:
|
||||
bullseye: [ros-noetic-bondpy]
|
||||
nodelet:
|
||||
debian:
|
||||
bullseye: [ros-noetic-nodelet]
|
||||
nodelet_tutorial_math:
|
||||
debian:
|
||||
bullseye: [ros-noetic-nodelet-tutorial-math]
|
||||
pluginlib_tutorials:
|
||||
debian:
|
||||
bullseye: [ros-noetic-pluginlib-tutorials]
|
||||
roscpp_tutorials:
|
||||
debian:
|
||||
bullseye: [ros-noetic-roscpp-tutorials]
|
||||
rosout:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosout]
|
||||
async_web_server_cpp:
|
||||
debian:
|
||||
bullseye: [ros-noetic-async-web-server-cpp]
|
||||
camera_calibration:
|
||||
debian:
|
||||
bullseye: [ros-noetic-camera-calibration]
|
||||
diagnostic_aggregator:
|
||||
debian:
|
||||
bullseye: [ros-noetic-diagnostic-aggregator]
|
||||
diagnostic_updater:
|
||||
debian:
|
||||
bullseye: [ros-noetic-diagnostic-updater]
|
||||
diagnostic_common_diagnostics:
|
||||
debian:
|
||||
bullseye: [ros-noetic-diagnostic-common-diagnostics]
|
||||
dynamic_reconfigure:
|
||||
debian:
|
||||
bullseye: [ros-noetic-dynamic-reconfigure]
|
||||
filters:
|
||||
debian:
|
||||
bullseye: [ros-noetic-filters]
|
||||
joint_state_publisher:
|
||||
debian:
|
||||
bullseye: [ros-noetic-joint-state-publisher]
|
||||
message_filters:
|
||||
debian:
|
||||
bullseye: [ros-noetic-message-filters]
|
||||
ros_pytest:
|
||||
debian:
|
||||
bullseye: [ros-noetic-ros-pytest]
|
||||
rosauth:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosauth]
|
||||
rosbag_storage:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosbag-storage]
|
||||
rosnode:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosnode]
|
||||
rospy_tutorials:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rospy-tutorials]
|
||||
rosshow:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosshow]
|
||||
rostopic:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rostopic]
|
||||
rqt_gui_cpp:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-gui-cpp]
|
||||
rqt_gui_py:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-gui-py]
|
||||
self_test:
|
||||
debian:
|
||||
bullseye: [ros-noetic-self-test]
|
||||
smach_ros:
|
||||
debian:
|
||||
bullseye: [ros-noetic-smach-ros]
|
||||
tf2_py:
|
||||
debian:
|
||||
bullseye: [ros-noetic-tf2-py]
|
||||
topic_tools:
|
||||
debian:
|
||||
bullseye: [ros-noetic-topic-tools]
|
||||
rosbag:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosbag]
|
||||
actionlib:
|
||||
debian:
|
||||
bullseye: [ros-noetic-actionlib]
|
||||
actionlib_tutorials:
|
||||
debian:
|
||||
bullseye: [ros-noetic-actionlib-tutorials]
|
||||
diagnostic_analysis:
|
||||
debian:
|
||||
bullseye: [ros-noetic-diagnostic-analysis]
|
||||
nodelet_topic_tools:
|
||||
debian:
|
||||
bullseye: [ros-noetic-nodelet-topic-tools]
|
||||
roswtf:
|
||||
debian:
|
||||
bullseye: [ros-noetic-roswtf]
|
||||
rqt_launch:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-launch]
|
||||
sensor_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-sensor-msgs]
|
||||
camera_calibration_parsers:
|
||||
debian:
|
||||
bullseye: [ros-noetic-camera-calibration-parsers]
|
||||
cv_bridge:
|
||||
debian:
|
||||
bullseye: [ros-noetic-cv-bridge]
|
||||
image_geometry:
|
||||
debian:
|
||||
bullseye: [ros-noetic-image-geometry]
|
||||
image_transport:
|
||||
debian:
|
||||
bullseye: [ros-noetic-image-transport]
|
||||
camera_info_manager:
|
||||
debian:
|
||||
bullseye: [ros-noetic-camera-info-manager]
|
||||
compressed_depth_image_transport:
|
||||
debian:
|
||||
bullseye: [ros-noetic-compressed-depth-image-transport]
|
||||
compressed_image_transport:
|
||||
debian:
|
||||
bullseye: [ros-noetic-compressed-image-transport]
|
||||
cv_camera:
|
||||
debian:
|
||||
bullseye: [ros-noetic-cv-camera]
|
||||
image_proc:
|
||||
debian:
|
||||
bullseye: [ros-noetic-image-proc]
|
||||
image_publisher:
|
||||
debian:
|
||||
bullseye: [ros-noetic-image-publisher]
|
||||
map_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-map-msgs]
|
||||
mavros_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-mavros-msgs]
|
||||
pcl_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-pcl-msgs]
|
||||
pcl_conversions:
|
||||
debian:
|
||||
bullseye: [ros-noetic-pcl-conversions]
|
||||
polled_camera:
|
||||
debian:
|
||||
bullseye: [ros-noetic-polled-camera]
|
||||
rqt_image_view:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-image-view]
|
||||
stereo_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-stereo-msgs]
|
||||
image_view:
|
||||
debian:
|
||||
bullseye: [ros-noetic-image-view]
|
||||
rosbridge_library:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rosbridge-library]
|
||||
stereo_image_proc:
|
||||
debian:
|
||||
bullseye: [ros-noetic-stereo-image-proc]
|
||||
tf2_ros:
|
||||
debian:
|
||||
bullseye: [ros-noetic-tf2-ros]
|
||||
depth_image_proc:
|
||||
debian:
|
||||
bullseye: [ros-noetic-depth-image-proc]
|
||||
mavros:
|
||||
debian:
|
||||
bullseye: [ros-noetic-mavros]
|
||||
tf:
|
||||
debian:
|
||||
bullseye: [ros-noetic-tf]
|
||||
interactive_markers:
|
||||
debian:
|
||||
bullseye: [ros-noetic-interactive-markers]
|
||||
interactive_marker_tutorials:
|
||||
debian:
|
||||
bullseye: [ros-noetic-interactive-marker-tutorials]
|
||||
laser_geometry:
|
||||
debian:
|
||||
bullseye: [ros-noetic-laser-geometry]
|
||||
laser_assembler:
|
||||
debian:
|
||||
bullseye: [ros-noetic-laser-assembler]
|
||||
laser_filters:
|
||||
debian:
|
||||
bullseye: [ros-noetic-laser-filters]
|
||||
pcl_ros:
|
||||
debian:
|
||||
bullseye: [ros-noetic-pcl-ros]
|
||||
tf2_geometry_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-tf2-geometry-msgs]
|
||||
image_rotate:
|
||||
debian:
|
||||
bullseye: [ros-noetic-image-rotate]
|
||||
tf2_kdl:
|
||||
debian:
|
||||
bullseye: [ros-noetic-tf2-kdl]
|
||||
tf2_web_republisher:
|
||||
debian:
|
||||
bullseye: [ros-noetic-tf2-web-republisher]
|
||||
tf_conversions:
|
||||
debian:
|
||||
bullseye: [ros-noetic-tf-conversions]
|
||||
theora_image_transport:
|
||||
debian:
|
||||
bullseye: [ros-noetic-theora-image-transport]
|
||||
turtlesim:
|
||||
debian:
|
||||
bullseye: [ros-noetic-turtlesim]
|
||||
turtle_actionlib:
|
||||
debian:
|
||||
bullseye: [ros-noetic-turtle-actionlib]
|
||||
turtle_tf:
|
||||
debian:
|
||||
bullseye: [ros-noetic-turtle-tf]
|
||||
turtle_tf2:
|
||||
debian:
|
||||
bullseye: [ros-noetic-turtle-tf2]
|
||||
urdf:
|
||||
debian:
|
||||
bullseye: [ros-noetic-urdf]
|
||||
kdl_parser:
|
||||
debian:
|
||||
bullseye: [ros-noetic-kdl-parser]
|
||||
kdl_parser_py:
|
||||
debian:
|
||||
bullseye: [ros-noetic-kdl-parser-py]
|
||||
mavros_extras:
|
||||
debian:
|
||||
bullseye: [ros-noetic-mavros-extras]
|
||||
robot_state_publisher:
|
||||
debian:
|
||||
bullseye: [ros-noetic-robot-state-publisher]
|
||||
rviz:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rviz]
|
||||
librviz_tutorial:
|
||||
debian:
|
||||
bullseye: [ros-noetic-librviz-tutorial]
|
||||
rqt_rviz:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rqt-rviz]
|
||||
rviz_plugin_tutorials:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rviz-plugin-tutorials]
|
||||
rviz_python_tutorial:
|
||||
debian:
|
||||
bullseye: [ros-noetic-rviz-python-tutorial]
|
||||
urdf_tutorial:
|
||||
debian:
|
||||
bullseye: [ros-noetic-urdf-tutorial]
|
||||
usb_cam:
|
||||
debian:
|
||||
bullseye: [ros-noetic-usb-cam]
|
||||
visualization_marker_tutorials:
|
||||
debian:
|
||||
bullseye: [ros-noetic-visualization-marker-tutorials]
|
||||
vl53l1x:
|
||||
debian:
|
||||
bullseye: [ros-noetic-vl53l1x]
|
||||
web_video_server:
|
||||
debian:
|
||||
bullseye: [ros-noetic-web-video-server]
|
||||
xacro:
|
||||
debian:
|
||||
bullseye: [ros-noetic-xacro]
|
||||
led_msgs:
|
||||
debian:
|
||||
bullseye: [ros-noetic-led-msgs]
|
||||
ws281x:
|
||||
debian:
|
||||
bullseye: [ros-noetic-ws281x]
|
||||
ddynamic_reconfigure:
|
||||
debian:
|
||||
bullseye: [ros-noetic-ddynamic-reconfigure]
|
||||
librealsense2:
|
||||
debian:
|
||||
bullseye: [ros-noetic-librealsense2]
|
||||
realsense2_camera:
|
||||
debian:
|
||||
bullseye: [ros-noetic-realsense2-camera]
|
||||
realsense2_description:
|
||||
debian:
|
||||
bullseye: [ros-noetic-realsense2-description]
|
||||
@@ -1,100 +0,0 @@
|
||||
#! /usr/bin/env bash
|
||||
|
||||
#
|
||||
# Script for building ROS packages from scratch
|
||||
#
|
||||
# Copyright (C) 2022 Copter Express Technologies
|
||||
#
|
||||
# Author: Oleg Kalachev <okalachev@gmail.com>
|
||||
#
|
||||
# Distributed under MIT License (available at https://opensource.org/licenses/MIT).
|
||||
# The above copyright notice and this permission notice shall be included in all
|
||||
# copies or substantial portions of the Software.
|
||||
#
|
||||
|
||||
set -ex # exit on error, echo commands
|
||||
|
||||
# http://wiki.ros.org/Installation/Source
|
||||
|
||||
export ROS_DISTRO=noetic
|
||||
. /etc/os-release # set $VERSION_CODENAME to Debian release code name
|
||||
export ROS_OS_OVERRIDE=debian:11:$VERSION_CODENAME
|
||||
|
||||
echo "=== Building ROS from scratch"
|
||||
|
||||
#echo "--- Adding sources"
|
||||
#echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list
|
||||
#curl -s https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | sudo apt-key add -
|
||||
|
||||
apt-get update
|
||||
apt-get install -y python3-distutils python3-rosdep python3-rosinstall-generator build-essential git # python3-vcstool
|
||||
|
||||
# install vcstool using pip
|
||||
curl https://bootstrap.pypa.io/get-pip.py -o get-pip.py && python3 get-pip.py && rm get-pip.py
|
||||
pip3 install -U vcstool
|
||||
|
||||
# sudo rosdep init
|
||||
rm /etc/ros/rosdep/sources.list.d/20-default.list
|
||||
rosdep init
|
||||
rosdep update
|
||||
|
||||
# rm /etc/ros/rosdep/sources.list.d/20-default.list && rosdep init
|
||||
# rosdep --os=debian:$VERSION_CODENAME update
|
||||
|
||||
echo "--- Create Catkin workspace to build ROS package"
|
||||
mkdir ~/ros_catkin_ws
|
||||
cd ~/ros_catkin_ws
|
||||
|
||||
echo "--- Download ROS sources"
|
||||
rosinstall_generator ros_base --rosdistro $ROS_DISTRO --deps --tar > noetic.rosinstall
|
||||
mkdir ./src
|
||||
vcs import --input noetic.rosinstall ./src
|
||||
|
||||
# https://answers.ros.org/question/343367/catkin-package-dependencies-issue-when-installing-ros-melodic-on-raspberry-pi-4/
|
||||
#sudo apt remove python-rospkg
|
||||
#sudo apt remove python-catkin-pkg
|
||||
##sudo apt --fix-broken install
|
||||
#sudo apt-get autoremove
|
||||
|
||||
echo "--- Install catkin_pkg"
|
||||
cd
|
||||
git clone https://github.com/ros-infrastructure/catkin_pkg.git
|
||||
cd catkin_pkg
|
||||
python3 setup.py install
|
||||
cd ~/ros_catkin_ws
|
||||
|
||||
echo "--- Resolve dependencies"
|
||||
rosdep install --from-paths ./src --ignore-packages-from-source --rosdistro $ROS_DISTRO -y --os=debian:$VERSION_CODENAME --skip-keys="python3-catkin-pkg python3-catkin-pkg-modules python3-rosdep-modules"
|
||||
|
||||
echo "--- Build ROS"
|
||||
# https://github.com/ros/catkin/issues/863#issuecomment-290392074
|
||||
./src/catkin/bin/catkin_make_isolated --install -DCMAKE_BUILD_TYPE=Release \
|
||||
-DSETUPTOOLS_DEB_LAYOUT=OFF \
|
||||
--install-space=/opt/ros/$ROS_DISTRO
|
||||
|
||||
# source ~/ros_catkin_ws/install_isolated/setup.bash
|
||||
source /opt/ros/$ROS_DISTRO/setup.bash
|
||||
|
||||
echo "--- List built ROS packages"
|
||||
set +x
|
||||
rospack list-names | while read line; do echo $line `rosversion $line`; done
|
||||
set -x
|
||||
|
||||
echo "--- Build Debian packages"
|
||||
apt-get install -y python3-bloom debhelper dpkg-dev libtinyxml-dev
|
||||
|
||||
# add rosdep file to help bloom-generate resolve missing bullseye dependencies
|
||||
echo "yaml file:///etc/ros/rosdep/noetic-bullseye.yaml" >> /etc/ros/rosdep/sources.list.d/20-default.list
|
||||
rosdep update
|
||||
|
||||
pip3 install setuptools==45.2.0 # https://github.com/ros/catkin/issues/863#issuecomment-1000446018
|
||||
|
||||
for file in `find . -name "package.xml" -not -path "*/debian/*"`; do
|
||||
cd $(dirname ${file})
|
||||
rm -rf debian
|
||||
bloom-generate rosdebian --os-name debian --os-version $VERSION_CODENAME --ros-distro $ROS_DISTRO --debug
|
||||
debian/rules binary # fakeroot is not needed as we are root
|
||||
cd -
|
||||
done
|
||||
|
||||
ls
|
||||
@@ -16,7 +16,7 @@
|
||||
set -e # Exit immidiately on non-zero result
|
||||
|
||||
# https://www.raspberrypi.org/software/operating-systems/#raspberry-pi-os-32-bit
|
||||
SOURCE_IMAGE="https://downloads.raspberrypi.com/raspios_lite_armhf/images/raspios_lite_armhf-2023-12-11/2023-12-11-raspios-bookworm-armhf-lite.img.xz"
|
||||
SOURCE_IMAGE="https://downloads.raspberrypi.org/raspios_lite_armhf/images/raspios_lite_armhf-2021-05-28/2021-05-07-raspios-buster-armhf-lite.zip"
|
||||
|
||||
export DEBIAN_FRONTEND=${DEBIAN_FRONTEND:='noninteractive'}
|
||||
export LANG=${LANG:='C.UTF-8'}
|
||||
@@ -104,7 +104,7 @@ ${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/butterf
|
||||
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/butterfly.socket' '/lib/systemd/system/'
|
||||
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/monkey.service' '/lib/systemd/system/'
|
||||
# software install
|
||||
# ${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} exec ${SCRIPTS_DIR}'/image-software.sh'
|
||||
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} exec ${SCRIPTS_DIR}'/image-software.sh'
|
||||
# network setup
|
||||
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} exec ${SCRIPTS_DIR}'/image-network.sh'
|
||||
# avahi setup
|
||||
@@ -113,14 +113,13 @@ ${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/avahi-s
|
||||
# If RPi then use a one thread to build a ROS package on RPi, else use all
|
||||
[[ $(arch) == 'armv7l' ]] && NUMBER_THREADS=1 || NUMBER_THREADS=$(nproc --all)
|
||||
# Clover
|
||||
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/noetic-bullseye.yaml' '/etc/ros/rosdep/'
|
||||
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/noetic-rosdep-clover.yaml' '/etc/ros/rosdep/'
|
||||
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/ros_python_paths' '/etc/sudoers.d/'
|
||||
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/pigpiod.service' '/lib/systemd/system/'
|
||||
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/launch.nanorc' '/usr/share/nano/'
|
||||
# ${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/kinetic-ros-clover.rosinstall' '/home/pi/ros_catkin_ws/'
|
||||
# Add rename script
|
||||
#${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} exec ${SCRIPTS_DIR}'/image-ros.sh' ${REPO_URL} ${IMAGE_VERSION} false false ${NUMBER_THREADS}
|
||||
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} exec ${SCRIPTS_DIR}'/image-build-ros.sh'
|
||||
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} exec ${SCRIPTS_DIR}'/image-ros.sh' ${REPO_URL} ${IMAGE_VERSION} false false ${NUMBER_THREADS}
|
||||
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} exec ${SCRIPTS_DIR}'/image-validate.sh'
|
||||
|
||||
${BUILDER_DIR}/image-resize.sh ${IMAGE_PATH}
|
||||
|
||||
@@ -4,6 +4,8 @@
|
||||
<arg name="direction_z" default="down"/> <!-- direction the camera points: down, up -->
|
||||
<arg name="direction_y" default="backward"/> <!-- direction the camera cable points: backward, forward -->
|
||||
<arg name="device" default="/dev/video0"/> <!-- v4l2 device -->
|
||||
<arg name="throttled_topic" default="true"/> <!-- enable throttled image topic -->
|
||||
<arg name="throttled_topic_rate" default="5.0"/> <!-- throttled image topic rate -->
|
||||
<arg name="simulator" default="false"/>
|
||||
|
||||
<node if="$(eval direction_z == 'down' and direction_y == 'backward')" pkg="tf2_ros" type="static_transform_publisher" name="main_camera_frame" args="0.05 0 -0.07 -1.5707963 0 3.1415926 base_link main_camera_optical"/>
|
||||
@@ -43,4 +45,8 @@
|
||||
<node pkg="clover" type="camera_markers" ns="main_camera" name="main_camera_markers">
|
||||
<param name="scale" value="3.0"/>
|
||||
</node>
|
||||
|
||||
<!-- image topic throttled -->
|
||||
<node pkg="topic_tools" name="main_camera_throttle" type="throttle" ns="main_camera"
|
||||
args="messages image_raw $(arg throttled_topic_rate) image_raw_throttled" if="$(arg throttled_topic)"/>
|
||||
</launch>
|
||||
|
||||
@@ -37,6 +37,7 @@
|
||||
#include <mavros_msgs/State.h>
|
||||
#include <mavros_msgs/StatusText.h>
|
||||
#include <mavros_msgs/ManualControl.h>
|
||||
#include <mavros_msgs/Altitude.h>
|
||||
|
||||
#include <clover/GetTelemetry.h>
|
||||
#include <clover/Navigate.h>
|
||||
@@ -54,6 +55,7 @@ using namespace clover;
|
||||
using mavros_msgs::PositionTarget;
|
||||
using mavros_msgs::AttitudeTarget;
|
||||
using mavros_msgs::Thrust;
|
||||
using mavros_msgs::Altitude;
|
||||
|
||||
// tf2
|
||||
tf2_ros::Buffer tf_buffer;
|
||||
@@ -96,10 +98,12 @@ Thrust thrust_msg;
|
||||
TwistStamped rates_msg;
|
||||
TransformStamped target, setpoint;
|
||||
geometry_msgs::TransformStamped body;
|
||||
geometry_msgs::TransformStamped terrain;
|
||||
|
||||
// State
|
||||
PoseStamped nav_start;
|
||||
PoseStamped setpoint_position, setpoint_position_transformed;
|
||||
Vector3Stamped setpoint_z, setpoint_z_transformed; // for z-only commands
|
||||
Vector3Stamped setpoint_velocity, setpoint_velocity_transformed;
|
||||
QuaternionStamped setpoint_attitude, setpoint_attitude_transformed;
|
||||
float setpoint_yaw_rate;
|
||||
@@ -122,6 +126,8 @@ enum setpoint_type_t setpoint_type = NONE;
|
||||
|
||||
enum { YAW, YAW_RATE, TOWARDS } setpoint_yaw_type;
|
||||
|
||||
bool setpoint_z_valid = false;
|
||||
|
||||
// Last received telemetry messages
|
||||
mavros_msgs::State state;
|
||||
mavros_msgs::StatusText statustext;
|
||||
@@ -173,6 +179,15 @@ void handleLocalPosition(const PoseStamped& pose)
|
||||
// TODO: terrain?, home?
|
||||
}
|
||||
|
||||
void handleAltitude(const Altitude& alt)
|
||||
{
|
||||
// publish terrain frame
|
||||
if (!std::isfinite(alt.bottom_clearance)) return;
|
||||
terrain.header.stamp = alt.header.stamp;
|
||||
terrain.transform.translation.z = -alt.bottom_clearance;
|
||||
transform_broadcaster->sendTransform(terrain);
|
||||
}
|
||||
|
||||
// wait for transform without interrupting publishing setpoints
|
||||
inline bool waitTransform(const string& target, const string& source,
|
||||
const ros::Time& stamp, const ros::Duration& timeout) // editorconfig-checker-disable-line
|
||||
@@ -421,6 +436,18 @@ void publish(const ros::Time stamp)
|
||||
}
|
||||
}
|
||||
|
||||
if (setpoint_z_valid && setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == POSITION) {
|
||||
setpoint_z.header.stamp = stamp;
|
||||
try {
|
||||
tf_buffer.transform(setpoint_z, setpoint_z_transformed, local_frame, ros::Duration(0.05));
|
||||
setpoint_position_transformed.pose.position.z = setpoint_z_transformed.vector.z;
|
||||
|
||||
} catch (const tf2::TransformException& e) {
|
||||
ROS_WARN_THROTTLE(10, "can't transform z coordinate from %s to %s, ignoring z coordinate",
|
||||
setpoint_z.header.frame_id.c_str(), local_frame.c_str());
|
||||
}
|
||||
}
|
||||
|
||||
if (setpoint_type == POSITION) {
|
||||
position_msg = setpoint_position_transformed;
|
||||
}
|
||||
@@ -556,7 +583,7 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
|
||||
|
||||
// look up for reference frame
|
||||
auto search = reference_frames.find(frame_id);
|
||||
const string& reference_frame = search == reference_frames.end() ? frame_id : search->second;
|
||||
const string& reference_frame = search == reference_frames.end() ? frame_id : search->second; // when not found it's the same frame
|
||||
|
||||
// Serve "partial" commands
|
||||
|
||||
@@ -583,22 +610,33 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
|
||||
}
|
||||
}
|
||||
|
||||
if (!auto_arm && std::isfinite(yaw_rate) &&
|
||||
isnan(x) && isnan(y) && isnan(z) && isnan(vx) && isnan(vy) && isnan(vz) &&
|
||||
isnan(pitch) && isnan(roll) && isnan(yaw) && isnan(thrust) &&
|
||||
if (!auto_arm && std::isfinite(z) &&
|
||||
isnan(x) && isnan(y) && isnan(vx) && isnan(vy) && isnan(vz) &&
|
||||
isnan(pitch) && isnan(roll) && isnan(thrust) &&
|
||||
isnan(lat) && isnan(lon)) {
|
||||
// change only the yaw rate
|
||||
if (setpoint_type == POSITION || setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == VELOCITY) {
|
||||
message = "Changing yaw rate only";
|
||||
// set only the z
|
||||
if (setpoint_type == POSITION || setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL) {
|
||||
if (!waitTransform(setpoint_position.header.frame_id, frame_id, stamp, transform_timeout))
|
||||
throw std::runtime_error("Can't transform from " + frame_id + " to " + setpoint_position.header.frame_id);
|
||||
|
||||
setpoint_yaw_type = YAW_RATE;
|
||||
setpoint_yaw_rate = yaw_rate;
|
||||
message = "Changing z only";
|
||||
|
||||
setpoint_z.header.frame_id = frame_id;
|
||||
setpoint_z.header.stamp = stamp;
|
||||
setpoint_z.vector.z = z;
|
||||
setpoint_z_valid = true;
|
||||
goto publish_setpoint;
|
||||
|
||||
} else {
|
||||
throw std::runtime_error("Setting yaw rate is possible only when position or velocity setpoints active");
|
||||
throw std::runtime_error("Setting z is possible only when position setpoint active");
|
||||
}
|
||||
}
|
||||
|
||||
// commands without z
|
||||
if (isnan(z) && setpoint_z_valid && (sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL || sp_type == POSITION)) {
|
||||
z = 0;
|
||||
}
|
||||
|
||||
// Serve normal commands
|
||||
|
||||
if (sp_type == NAVIGATE || sp_type == POSITION) {
|
||||
@@ -860,6 +898,13 @@ bool land(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
|
||||
return false;
|
||||
}
|
||||
|
||||
bool release(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
|
||||
{
|
||||
setpoint_timer.stop();
|
||||
res.success = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
ros::init(argc, argv, "simple_offboard");
|
||||
@@ -881,6 +926,7 @@ int main(int argc, char **argv)
|
||||
nh_priv.param("check_kill_switch", check_kill_switch, true);
|
||||
nh_priv.param("default_speed", default_speed, 0.5f);
|
||||
nh_priv.param<string>("body_frame", body.child_frame_id, "body");
|
||||
nh_priv.param<string>("terrain_frame", terrain.child_frame_id, "terrain");
|
||||
nh_priv.getParam("reference_frames", reference_frames);
|
||||
|
||||
// Default reference frames
|
||||
@@ -916,6 +962,13 @@ int main(int argc, char **argv)
|
||||
auto manual_control_sub = nh.subscribe(mavros + "/manual_control/control", 1, &handleMessage<mavros_msgs::ManualControl, manual_control>);
|
||||
auto local_position_sub = nh.subscribe(mavros + "/local_position/pose", 1, &handleLocalPosition);
|
||||
|
||||
ros::Subscriber altitude_sub;
|
||||
if (!body.child_frame_id.empty() && !terrain.child_frame_id.empty()) {
|
||||
terrain.header.frame_id = body.child_frame_id;
|
||||
terrain.transform.rotation = tf::createQuaternionMsgFromRollPitchYaw(0, 0, 0);
|
||||
altitude_sub = nh.subscribe(mavros + "/altitude", 1, &handleAltitude);
|
||||
}
|
||||
|
||||
// Setpoint publishers
|
||||
position_pub = nh.advertise<PoseStamped>(mavros + "/setpoint_position/local", 1);
|
||||
position_raw_pub = nh.advertise<PositionTarget>(mavros + "/setpoint_raw/local", 1);
|
||||
@@ -933,6 +986,7 @@ int main(int argc, char **argv)
|
||||
auto sa_serv = nh.advertiseService("set_attitude", &setAttitude);
|
||||
auto sr_serv = nh.advertiseService("set_rates", &setRates);
|
||||
auto ld_serv = nh.advertiseService("land", &land);
|
||||
auto rl_serv = nh_priv.advertiseService("release", &release);
|
||||
|
||||
// Setpoint timer
|
||||
setpoint_timer = nh.createTimer(ros::Duration(1 / nh_priv.param("setpoint_rate", 30.0)), &publishSetpoint, false, false);
|
||||
|
||||
@@ -24,6 +24,7 @@ def test_simple_offboard_services_available():
|
||||
rospy.wait_for_service('set_attitude', timeout=5)
|
||||
rospy.wait_for_service('set_rates', timeout=5)
|
||||
rospy.wait_for_service('land', timeout=5)
|
||||
rospy.wait_for_service('simple_offboard/release', timeout=5)
|
||||
|
||||
def test_web_video_server(node):
|
||||
try:
|
||||
|
||||
@@ -37,6 +37,9 @@
|
||||
|
||||
<node name="clover_blocks" pkg="clover_blocks" type="clover_blocks" output="screen" required="true"/>
|
||||
|
||||
<node pkg="topic_tools" name="main_camera_throttle" type="throttle" ns="main_camera"
|
||||
args="messages image_raw 5.0 image_raw_throttled" required="true"/>
|
||||
|
||||
<param name="test_module" value="$(find clover)/test/basic.py"/>
|
||||
<test test-name="basic_test" pkg="ros_pytest" type="ros_pytest_runner"/>
|
||||
</launch>
|
||||
|
||||
@@ -145,6 +145,8 @@ rospy.spin()
|
||||
|
||||
The script will take up to 100% CPU capacity. To slow down the script artificially, you can use [throttling](http://wiki.ros.org/topic_tools/throttle) of frames from the camera, for example, at 5 Hz (`main_camera.launch`):
|
||||
|
||||
> **Note** Starting from [image](image.md) version **0.24** `image_raw_throttled` topic is available without addition configuration.
|
||||
|
||||
```xml
|
||||
<node pkg="topic_tools" name="cam_throttle" type="throttle"
|
||||
args="messages main_camera/image_raw 5.0 main_camera/image_raw_throttled"/>
|
||||
|
||||
@@ -305,6 +305,16 @@ rosservice call /land "{}"
|
||||
|
||||
> **Caution** In recent PX4 versions, the vehicle will be switched out of LAND mode to manual mode, if the remote control sticks are moved significantly.
|
||||
|
||||
### release
|
||||
|
||||
If it's necessary to pause sending setpoint messages, use the `simple_offboard/release` service:
|
||||
|
||||
```python
|
||||
release = rospy.ServiceProxy('simple_offboard/release', Trigger)
|
||||
|
||||
release()
|
||||
```
|
||||
|
||||
## Additional materials
|
||||
|
||||
* [ArUco-based position estimation and navigation](aruco.md).
|
||||
|
||||
@@ -147,6 +147,8 @@ rospy.spin()
|
||||
|
||||
Скрипт будет занимать 100% процессора. Для искусственного замедления работы скрипта можно запустить [throttling](http://wiki.ros.org/topic_tools/throttle) кадров с камеры, например, в 5 Гц (`main_camera.launch`):
|
||||
|
||||
> **Note** Начиная с версии [образа](image.md) **0.24** топик `image_raw_throttled` доступен без дополнительной конфигурации.
|
||||
|
||||
```xml
|
||||
<node pkg="topic_tools" name="cam_throttle" type="throttle"
|
||||
args="messages main_camera/image_raw 5.0 main_camera/image_raw_throttled"/>
|
||||
|
||||
@@ -305,6 +305,16 @@ rosservice call /land "{}"
|
||||
|
||||
> **Caution** В более новых версиях PX4 коптер выйдет из режима LAND в ручной режим, если сильно перемещать стики.
|
||||
|
||||
### release
|
||||
|
||||
В случае необходимости приостановки отправки setpoint-сообщений, используйте сервис `simple_offboard/release`:
|
||||
|
||||
```python
|
||||
release = rospy.ServiceProxy('simple_offboard/release', Trigger)
|
||||
|
||||
release()
|
||||
```
|
||||
|
||||
## Дополнительные материалы
|
||||
|
||||
* [Полеты в поле ArUco-маркеров](aruco.md).
|
||||
|
||||
Reference in New Issue
Block a user