mirror of
https://github.com/CopterExpress/clover.git
synced 2026-06-01 15:39:32 +00:00
Compare commits
5 Commits
bullseye
...
navigate-f
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
b3e8334c60 | ||
|
|
0f5f111f46 | ||
|
|
4e9d8a64d0 | ||
|
|
94171d51ac | ||
|
|
eb448ae0e7 |
@@ -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
|
set -e # Exit immidiately on non-zero result
|
||||||
|
|
||||||
# https://www.raspberrypi.org/software/operating-systems/#raspberry-pi-os-32-bit
|
# 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 DEBIAN_FRONTEND=${DEBIAN_FRONTEND:='noninteractive'}
|
||||||
export LANG=${LANG:='C.UTF-8'}
|
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/butterfly.socket' '/lib/systemd/system/'
|
||||||
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/monkey.service' '/lib/systemd/system/'
|
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/monkey.service' '/lib/systemd/system/'
|
||||||
# software install
|
# 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
|
# network setup
|
||||||
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} exec ${SCRIPTS_DIR}'/image-network.sh'
|
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} exec ${SCRIPTS_DIR}'/image-network.sh'
|
||||||
# avahi setup
|
# 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
|
# 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)
|
[[ $(arch) == 'armv7l' ]] && NUMBER_THREADS=1 || NUMBER_THREADS=$(nproc --all)
|
||||||
# Clover
|
# 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/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/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/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/'
|
# ${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/kinetic-ros-clover.rosinstall' '/home/pi/ros_catkin_ws/'
|
||||||
# Add rename script
|
# 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-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-validate.sh'
|
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} exec ${SCRIPTS_DIR}'/image-validate.sh'
|
||||||
|
|
||||||
${BUILDER_DIR}/image-resize.sh ${IMAGE_PATH}
|
${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_z" default="down"/> <!-- direction the camera points: down, up -->
|
||||||
<arg name="direction_y" default="backward"/> <!-- direction the camera cable points: backward, forward -->
|
<arg name="direction_y" default="backward"/> <!-- direction the camera cable points: backward, forward -->
|
||||||
<arg name="device" default="/dev/video0"/> <!-- v4l2 device -->
|
<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"/>
|
<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"/>
|
<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">
|
<node pkg="clover" type="camera_markers" ns="main_camera" name="main_camera_markers">
|
||||||
<param name="scale" value="3.0"/>
|
<param name="scale" value="3.0"/>
|
||||||
</node>
|
</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>
|
</launch>
|
||||||
|
|||||||
@@ -78,6 +78,7 @@ ros::Duration manual_control_timeout;
|
|||||||
float default_speed;
|
float default_speed;
|
||||||
bool auto_release;
|
bool auto_release;
|
||||||
bool land_only_in_offboard, nav_from_sp, check_kill_switch;
|
bool land_only_in_offboard, nav_from_sp, check_kill_switch;
|
||||||
|
bool nav_feedforward;
|
||||||
std::map<string, string> reference_frames;
|
std::map<string, string> reference_frames;
|
||||||
|
|
||||||
// Publishers
|
// Publishers
|
||||||
@@ -94,6 +95,7 @@ PositionTarget position_raw_msg;
|
|||||||
AttitudeTarget att_raw_msg;
|
AttitudeTarget att_raw_msg;
|
||||||
Thrust thrust_msg;
|
Thrust thrust_msg;
|
||||||
TwistStamped rates_msg;
|
TwistStamped rates_msg;
|
||||||
|
Vector3 velocity_feedforward;
|
||||||
TransformStamped target, setpoint;
|
TransformStamped target, setpoint;
|
||||||
geometry_msgs::TransformStamped body;
|
geometry_msgs::TransformStamped body;
|
||||||
|
|
||||||
@@ -341,7 +343,15 @@ inline float getDistance(const Point& from, const Point& to)
|
|||||||
return hypot(from.x - to.x, from.y - to.y, from.z - to.z);
|
return hypot(from.x - to.x, from.y - to.y, from.z - to.z);
|
||||||
}
|
}
|
||||||
|
|
||||||
void getNavigateSetpoint(const ros::Time& stamp, float speed, Point& nav_setpoint)
|
inline void normalize(Vector3& vector, double length = 1.0)
|
||||||
|
{
|
||||||
|
double len = hypot(vector.x, vector.y, vector.z);
|
||||||
|
vector.x *= length / len;
|
||||||
|
vector.y *= length / len;
|
||||||
|
vector.z *= length / len;
|
||||||
|
}
|
||||||
|
|
||||||
|
void getNavigateSetpoint(const ros::Time& stamp, float speed, Point& nav_setpoint, Vector3& velocity_feedforward)
|
||||||
{
|
{
|
||||||
if (wait_armed) {
|
if (wait_armed) {
|
||||||
// don't start navigating if we're waiting arming
|
// don't start navigating if we're waiting arming
|
||||||
@@ -355,6 +365,14 @@ void getNavigateSetpoint(const ros::Time& stamp, float speed, Point& nav_setpoin
|
|||||||
nav_setpoint.x = nav_start.pose.position.x + (setpoint_position_transformed.pose.position.x - nav_start.pose.position.x) * passed;
|
nav_setpoint.x = nav_start.pose.position.x + (setpoint_position_transformed.pose.position.x - nav_start.pose.position.x) * passed;
|
||||||
nav_setpoint.y = nav_start.pose.position.y + (setpoint_position_transformed.pose.position.y - nav_start.pose.position.y) * passed;
|
nav_setpoint.y = nav_start.pose.position.y + (setpoint_position_transformed.pose.position.y - nav_start.pose.position.y) * passed;
|
||||||
nav_setpoint.z = nav_start.pose.position.z + (setpoint_position_transformed.pose.position.z - nav_start.pose.position.z) * passed;
|
nav_setpoint.z = nav_start.pose.position.z + (setpoint_position_transformed.pose.position.z - nav_start.pose.position.z) * passed;
|
||||||
|
|
||||||
|
if (nav_feedforward) {
|
||||||
|
// calculate velocity feedforward
|
||||||
|
velocity_feedforward.x = setpoint_position_transformed.pose.position.x - nav_start.pose.position.x;
|
||||||
|
velocity_feedforward.y = setpoint_position_transformed.pose.position.y - nav_start.pose.position.y;
|
||||||
|
velocity_feedforward.z = setpoint_position_transformed.pose.position.z - nav_start.pose.position.z;
|
||||||
|
normalize(velocity_feedforward, speed);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
PoseStamped globalToLocal(double lat, double lon)
|
PoseStamped globalToLocal(double lat, double lon)
|
||||||
@@ -412,7 +430,7 @@ void publish(const ros::Time stamp)
|
|||||||
|
|
||||||
if (setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL) {
|
if (setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL) {
|
||||||
position_msg.pose.orientation = setpoint_position_transformed.pose.orientation; // copy yaw
|
position_msg.pose.orientation = setpoint_position_transformed.pose.orientation; // copy yaw
|
||||||
getNavigateSetpoint(stamp, nav_speed, position_msg.pose.position);
|
getNavigateSetpoint(stamp, nav_speed, position_msg.pose.position, velocity_feedforward);
|
||||||
|
|
||||||
if (setpoint_yaw_type == TOWARDS) {
|
if (setpoint_yaw_type == TOWARDS) {
|
||||||
double yaw_towards = atan2(position_msg.pose.position.y - nav_start.pose.position.y,
|
double yaw_towards = atan2(position_msg.pose.position.y - nav_start.pose.position.y,
|
||||||
@@ -428,19 +446,31 @@ void publish(const ros::Time stamp)
|
|||||||
if (setpoint_type == POSITION || setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL) {
|
if (setpoint_type == POSITION || setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL) {
|
||||||
position_msg.header.stamp = stamp;
|
position_msg.header.stamp = stamp;
|
||||||
|
|
||||||
if (setpoint_yaw_type == YAW || setpoint_yaw_type == TOWARDS) {
|
if (!nav_feedforward && setpoint_yaw_type == YAW || setpoint_yaw_type == TOWARDS) {
|
||||||
|
// simple pose setpoint without velocity feedforward and yaw rate
|
||||||
position_pub.publish(position_msg);
|
position_pub.publish(position_msg);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
position_raw_msg.type_mask = PositionTarget::IGNORE_VX +
|
position_raw_msg.type_mask = PositionTarget::IGNORE_AFX +
|
||||||
PositionTarget::IGNORE_VY +
|
|
||||||
PositionTarget::IGNORE_VZ +
|
|
||||||
PositionTarget::IGNORE_AFX +
|
|
||||||
PositionTarget::IGNORE_AFY +
|
PositionTarget::IGNORE_AFY +
|
||||||
PositionTarget::IGNORE_AFZ +
|
PositionTarget::IGNORE_AFZ;
|
||||||
PositionTarget::IGNORE_YAW;
|
|
||||||
|
if (!nav_feedforward) {
|
||||||
|
position_raw_msg.type_mask = PositionTarget::IGNORE_VX +
|
||||||
|
PositionTarget::IGNORE_VY +
|
||||||
|
PositionTarget::IGNORE_VZ;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
position_raw_msg.type_mask += setpoint_yaw_type == YAW_RATE ?
|
||||||
|
PositionTarget::IGNORE_YAW : PositionTarget::IGNORE_YAW_RATE;
|
||||||
|
|
||||||
position_raw_msg.yaw_rate = setpoint_yaw_rate;
|
position_raw_msg.yaw_rate = setpoint_yaw_rate;
|
||||||
|
position_raw_msg.yaw = setpoint_yaw;
|
||||||
position_raw_msg.position = position_msg.pose.position;
|
position_raw_msg.position = position_msg.pose.position;
|
||||||
|
position_raw_msg.velocity.x = velocity_feedforward.x;
|
||||||
|
position_raw_msg.velocity.y = velocity_feedforward.y;
|
||||||
|
position_raw_msg.velocity.z = velocity_feedforward.z;
|
||||||
position_raw_pub.publish(position_raw_msg);
|
position_raw_pub.publish(position_raw_msg);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -860,6 +890,13 @@ bool land(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
|
|||||||
return false;
|
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)
|
int main(int argc, char **argv)
|
||||||
{
|
{
|
||||||
ros::init(argc, argv, "simple_offboard");
|
ros::init(argc, argv, "simple_offboard");
|
||||||
@@ -879,6 +916,7 @@ int main(int argc, char **argv)
|
|||||||
nh_priv.param("land_only_in_offboard", land_only_in_offboard, true);
|
nh_priv.param("land_only_in_offboard", land_only_in_offboard, true);
|
||||||
nh_priv.param("nav_from_sp", nav_from_sp, true);
|
nh_priv.param("nav_from_sp", nav_from_sp, true);
|
||||||
nh_priv.param("check_kill_switch", check_kill_switch, true);
|
nh_priv.param("check_kill_switch", check_kill_switch, true);
|
||||||
|
nh_priv.param("nav_feedforward", nav_feedforward, true);
|
||||||
nh_priv.param("default_speed", default_speed, 0.5f);
|
nh_priv.param("default_speed", default_speed, 0.5f);
|
||||||
nh_priv.param<string>("body_frame", body.child_frame_id, "body");
|
nh_priv.param<string>("body_frame", body.child_frame_id, "body");
|
||||||
nh_priv.getParam("reference_frames", reference_frames);
|
nh_priv.getParam("reference_frames", reference_frames);
|
||||||
@@ -933,6 +971,7 @@ int main(int argc, char **argv)
|
|||||||
auto sa_serv = nh.advertiseService("set_attitude", &setAttitude);
|
auto sa_serv = nh.advertiseService("set_attitude", &setAttitude);
|
||||||
auto sr_serv = nh.advertiseService("set_rates", &setRates);
|
auto sr_serv = nh.advertiseService("set_rates", &setRates);
|
||||||
auto ld_serv = nh.advertiseService("land", &land);
|
auto ld_serv = nh.advertiseService("land", &land);
|
||||||
|
auto rl_serv = nh_priv.advertiseService("release", &release);
|
||||||
|
|
||||||
// Setpoint timer
|
// Setpoint timer
|
||||||
setpoint_timer = nh.createTimer(ros::Duration(1 / nh_priv.param("setpoint_rate", 30.0)), &publishSetpoint, false, false);
|
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_attitude', timeout=5)
|
||||||
rospy.wait_for_service('set_rates', timeout=5)
|
rospy.wait_for_service('set_rates', timeout=5)
|
||||||
rospy.wait_for_service('land', timeout=5)
|
rospy.wait_for_service('land', timeout=5)
|
||||||
|
rospy.wait_for_service('simple_offboard/release', timeout=5)
|
||||||
|
|
||||||
def test_web_video_server(node):
|
def test_web_video_server(node):
|
||||||
try:
|
try:
|
||||||
|
|||||||
@@ -37,6 +37,9 @@
|
|||||||
|
|
||||||
<node name="clover_blocks" pkg="clover_blocks" type="clover_blocks" output="screen" required="true"/>
|
<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"/>
|
<param name="test_module" value="$(find clover)/test/basic.py"/>
|
||||||
<test test-name="basic_test" pkg="ros_pytest" type="ros_pytest_runner"/>
|
<test test-name="basic_test" pkg="ros_pytest" type="ros_pytest_runner"/>
|
||||||
</launch>
|
</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`):
|
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
|
```xml
|
||||||
<node pkg="topic_tools" name="cam_throttle" type="throttle"
|
<node pkg="topic_tools" name="cam_throttle" type="throttle"
|
||||||
args="messages main_camera/image_raw 5.0 main_camera/image_raw_throttled"/>
|
args="messages main_camera/image_raw 5.0 main_camera/image_raw_throttled"/>
|
||||||
|
|||||||
@@ -103,7 +103,7 @@ Parameters:
|
|||||||
* `yaw_rate` – angular yaw velocity (will be used if yaw is set to `NaN`) *(rad/s)*;
|
* `yaw_rate` – angular yaw velocity (will be used if yaw is set to `NaN`) *(rad/s)*;
|
||||||
* `speed` – flight speed (setpoint speed) *(m/s)*;
|
* `speed` – flight speed (setpoint speed) *(m/s)*;
|
||||||
* `auto_arm` – switch the drone to `OFFBOARD` mode and arm automatically (**the drone will take off**);
|
* `auto_arm` – switch the drone to `OFFBOARD` mode and arm automatically (**the drone will take off**);
|
||||||
* `frame_id` – [coordinate system](frames.md) for values `x`, `y`, `z`, `vx`, `vy`, `vz`. Example: `map`, `body`, `aruco_map`. Default value: `map`.
|
* `frame_id` – [coordinate system](frames.md) for values `x`, `y`, `z` and `yaw`. Example: `map`, `body`, `aruco_map`. Default value: `map`.
|
||||||
|
|
||||||
> **Note** If you don't want to change your current yaw set the `yaw` parameter to `NaN` (angular velocity by default is 0).
|
> **Note** If you don't want to change your current yaw set the `yaw` parameter to `NaN` (angular velocity by default is 0).
|
||||||
|
|
||||||
@@ -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.
|
> **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
|
## Additional materials
|
||||||
|
|
||||||
* [ArUco-based position estimation and navigation](aruco.md).
|
* [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`):
|
Скрипт будет занимать 100% процессора. Для искусственного замедления работы скрипта можно запустить [throttling](http://wiki.ros.org/topic_tools/throttle) кадров с камеры, например, в 5 Гц (`main_camera.launch`):
|
||||||
|
|
||||||
|
> **Note** Начиная с версии [образа](image.md) **0.24** топик `image_raw_throttled` доступен без дополнительной конфигурации.
|
||||||
|
|
||||||
```xml
|
```xml
|
||||||
<node pkg="topic_tools" name="cam_throttle" type="throttle"
|
<node pkg="topic_tools" name="cam_throttle" type="throttle"
|
||||||
args="messages main_camera/image_raw 5.0 main_camera/image_raw_throttled"/>
|
args="messages main_camera/image_raw 5.0 main_camera/image_raw_throttled"/>
|
||||||
|
|||||||
@@ -305,6 +305,16 @@ rosservice call /land "{}"
|
|||||||
|
|
||||||
> **Caution** В более новых версиях PX4 коптер выйдет из режима LAND в ручной режим, если сильно перемещать стики.
|
> **Caution** В более новых версиях PX4 коптер выйдет из режима LAND в ручной режим, если сильно перемещать стики.
|
||||||
|
|
||||||
|
### release
|
||||||
|
|
||||||
|
В случае необходимости приостановки отправки setpoint-сообщений, используйте сервис `simple_offboard/release`:
|
||||||
|
|
||||||
|
```python
|
||||||
|
release = rospy.ServiceProxy('simple_offboard/release', Trigger)
|
||||||
|
|
||||||
|
release()
|
||||||
|
```
|
||||||
|
|
||||||
## Дополнительные материалы
|
## Дополнительные материалы
|
||||||
|
|
||||||
* [Полеты в поле ArUco-маркеров](aruco.md).
|
* [Полеты в поле ArUco-маркеров](aruco.md).
|
||||||
|
|||||||
Reference in New Issue
Block a user