diff --git a/call_attitude.sh b/call_attitude.sh new file mode 100755 index 00000000..89ddf4e7 --- /dev/null +++ b/call_attitude.sh @@ -0,0 +1 @@ +ros2 service call /drone/set_attitude drone_services/srv/SetAttitude "{pitch: $1, yaw: $2, roll: $3, thrust: $4}" diff --git a/src/px4_connection/CMakeLists.txt b/src/px4_connection/CMakeLists.txt index 7a16c5c1..f41b9cb8 100644 --- a/src/px4_connection/CMakeLists.txt +++ b/src/px4_connection/CMakeLists.txt @@ -28,6 +28,7 @@ add_executable(heartbeat src/heartbeat.cpp) ament_target_dependencies( heartbeat rclcpp + drone_services px4_ros_com px4_msgs drone_services diff --git a/src/px4_connection/src/heartbeat.cpp b/src/px4_connection/src/heartbeat.cpp index 330a85ed..8aafbf10 100644 --- a/src/px4_connection/src/heartbeat.cpp +++ b/src/px4_connection/src/heartbeat.cpp @@ -1,3 +1,4 @@ + /** * @file heartbeat.cpp * @author Sem van der Hoeven (sem.hoeven@gmail.com) @@ -62,15 +63,6 @@ private: msg.attitude = (this->control_mode >> CONTROL_ATTITUDE_POS) & 1 ? true : false; msg.body_rate = (this->control_mode >> CONTROL_BODY_RATE_POS) & 1 ? true : false; msg.actuator = (this->control_mode >> CONTROL_ACTUATOR_POS) & 1 ? true : false; - - /* - msg.position = false; - msg.velocity = false; - msg.acceleration = false; - msg.attitude = true; - msg.body_rate = false; - msg.actuator = false; - */ // get timestamp and publish message msg.timestamp = this->get_clock()->now().nanoseconds() / 1000; offboard_control_mode_publisher_->publish(msg); diff --git a/src/px4_msgs b/src/px4_msgs index b64ef047..ffc3a4cd 160000 --- a/src/px4_msgs +++ b/src/px4_msgs @@ -1 +1 @@ -Subproject commit b64ef0475c1d44605688f4770899fe453d532be4 +Subproject commit ffc3a4cd578776213a444abe17d7eabf9621b266