Path: blob/master/libraries/AP_DDS/AP_DDS_ExternalControl.cpp
9381 views
#include "AP_DDS_config.h"12#if AP_DDS_ENABLED34#include "AP_DDS_ExternalControl.h"5#include "AP_DDS_Frames.h"6#include <AP_AHRS/AP_AHRS.h>78#include <AP_ExternalControl/AP_ExternalControl.h>910bool AP_DDS_External_Control::handle_global_position_control(ardupilot_msgs_msg_GlobalPosition& cmd_pos)11{12auto *external_control = AP::externalcontrol();13if (external_control == nullptr) {14return false;15}1617if (strcmp(cmd_pos.header.frame_id, MAP_FRAME) == 0) {18// Narrow the altitude19const int32_t alt_cm = static_cast<int32_t>(cmd_pos.altitude * 100);2021Location::AltFrame alt_frame;22if (!convert_alt_frame(cmd_pos.coordinate_frame, alt_frame)) {23return false;24}2526constexpr uint32_t MASK_POS_IGNORE =27GlobalPosition::IGNORE_LATITUDE |28GlobalPosition::IGNORE_LONGITUDE |29GlobalPosition::IGNORE_ALTITUDE;3031if (!(cmd_pos.type_mask & MASK_POS_IGNORE)) {32Location loc(cmd_pos.latitude * 1E7, cmd_pos.longitude * 1E7, alt_cm, alt_frame);33if (!external_control->set_global_position(loc)) {34return false; // Don't try sending other commands if this fails35}36}3738// TODO add velocity and accel handling3940return true;41}4243return false;44}4546bool AP_DDS_External_Control::handle_velocity_control(geometry_msgs_msg_TwistStamped& cmd_vel)47{48auto *external_control = AP::externalcontrol();49if (external_control == nullptr) {50return false;51}5253if (strcmp(cmd_vel.header.frame_id, BASE_LINK_FRAME_ID) == 0) {54// Convert commands from body frame (x-forward, y-left, z-up) to NED.55Vector3f linear_velocity;56Vector3f linear_velocity_base_link {57float(cmd_vel.twist.linear.x),58float(cmd_vel.twist.linear.y),59float(-cmd_vel.twist.linear.z) };6061if (isnan(linear_velocity_base_link.y) && isnan(linear_velocity_base_link.z)) {62// Assume it's an airspeed command so ignore the angular data.63// While MAV_CMD_GUIDED_CHANGE_SPEED supports commands of ground speed and airspeed,64// ROS users likely care more about airspeed control for a low level velocity control interface like this.65return external_control->set_airspeed(linear_velocity_base_link.x);66}6768const float yaw_rate = -cmd_vel.twist.angular.z;6970auto &ahrs = AP::ahrs();71linear_velocity = ahrs.body_to_earth(linear_velocity_base_link);72return external_control->set_linear_velocity_and_yaw_rate(linear_velocity, yaw_rate);73}7475else if (strcmp(cmd_vel.header.frame_id, MAP_FRAME) == 0) {76// Convert commands from ENU to NED frame77Vector3f linear_velocity {78float(cmd_vel.twist.linear.y),79float(cmd_vel.twist.linear.x),80float(-cmd_vel.twist.linear.z) };81const float yaw_rate = -cmd_vel.twist.angular.z;82return external_control->set_linear_velocity_and_yaw_rate(linear_velocity, yaw_rate);83}8485return false;86}8788bool AP_DDS_External_Control::arm(AP_Arming::Method method, bool do_arming_checks)89{90auto *external_control = AP::externalcontrol();91if (external_control == nullptr) {92return false;93}9495return external_control->arm(method, do_arming_checks);96}9798bool AP_DDS_External_Control::disarm(AP_Arming::Method method, bool do_disarm_checks)99{100auto *external_control = AP::externalcontrol();101if (external_control == nullptr) {102return false;103}104105return external_control->disarm(method, do_disarm_checks);106}107108bool AP_DDS_External_Control::convert_alt_frame(const uint8_t frame_in, Location::AltFrame& frame_out)109{110111// Specified in ROS REP-147; only some are supported.112switch (frame_in) {113case 5: // FRAME_GLOBAL_INT114frame_out = Location::AltFrame::ABSOLUTE;115break;116case 6: // FRAME_GLOBAL_REL_ALT117frame_out = Location::AltFrame::ABOVE_HOME;118break;119case 11: // FRAME_GLOBAL_TERRAIN_ALT120frame_out = Location::AltFrame::ABOVE_TERRAIN;121break;122default:123return false;124}125return true;126}127128129#endif // AP_DDS_ENABLED130131