File tree Expand file tree Collapse file tree 1 file changed +3
-2
lines changed
terrain_navigation_ros/src Expand file tree Collapse file tree 1 file changed +3
-2
lines changed Original file line number Diff line number Diff line change @@ -765,7 +765,8 @@ void TerrainPlanner::publishGlobalPositionSetpoints(
765765 mavros_msgs::msg::GlobalPositionTarget msg;
766766 msg.header .stamp = this ->get_clock ()->now ();
767767 msg.coordinate_frame = mavros_msgs::msg::GlobalPositionTarget::FRAME_GLOBAL_REL_ALT;
768- msg.type_mask = 0.0 ;
768+ msg.type_mask =
769+ mavros_msgs::msg::GlobalPositionTarget::IGNORE_YAW | mavros_msgs::msg::GlobalPositionTarget::IGNORE_YAW_RATE;
769770 msg.latitude = latitude;
770771 msg.longitude = longitude;
771772 msg.altitude = altitude - local_origin_altitude_;
@@ -790,7 +791,7 @@ void TerrainPlanner::publishPositionSetpoints(rclcpp::Publisher<mavros_msgs::msg
790791 mavros_msgs::msg::PositionTarget msg;
791792 msg.header .stamp = this ->get_clock ()->now ();
792793 msg.coordinate_frame = mavros_msgs::msg::PositionTarget::FRAME_LOCAL_NED;
793- msg.type_mask = 0.0 ;
794+ msg.type_mask = mavros_msgs::msg::PositionTarget::IGNORE_YAW | mavros_msgs::msg::PositionTarget::IGNORE_YAW_RATE ;
794795 msg.position .x = position (0 );
795796 msg.position .y = position (1 );
796797 msg.position .z = position (2 );
You can’t perform that action at this time.
0 commit comments