mirror of https://github.com/ArduPilot/ardupilot
AP_DDS: Accept body-frame velocity inputs
This commit is contained in:
parent
198268e03c
commit
62b15a8af0
|
@ -2,6 +2,7 @@
|
||||||
|
|
||||||
#include "AP_DDS_ExternalControl.h"
|
#include "AP_DDS_ExternalControl.h"
|
||||||
#include "AP_DDS_Frames.h"
|
#include "AP_DDS_Frames.h"
|
||||||
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
|
|
||||||
#include <AP_ExternalControl/AP_ExternalControl.h>
|
#include <AP_ExternalControl/AP_ExternalControl.h>
|
||||||
|
|
||||||
|
@ -11,21 +12,32 @@ bool AP_DDS_External_Control::handle_velocity_control(geometry_msgs_msg_TwistSta
|
||||||
if (external_control == nullptr) {
|
if (external_control == nullptr) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
if (strcmp(cmd_vel.header.frame_id, MAP_FRAME) != 0) {
|
|
||||||
// Although REP-147 says cmd_vel should be in body frame, all the AP math is done in earth frame.
|
if (strcmp(cmd_vel.header.frame_id, BASE_LINK_FRAME_ID) == 0) {
|
||||||
// This is because accounting for the gravity vector.
|
// Convert commands from body frame (x-forward, y-left, z-up) to NED.
|
||||||
// Although the ROS 2 interface could support body-frame velocity control in the future,
|
Vector3f linear_velocity;
|
||||||
// it is currently not supported.
|
Vector3f linear_velocity_base_link {
|
||||||
return false;
|
float(cmd_vel.twist.linear.x),
|
||||||
|
float(cmd_vel.twist.linear.y),
|
||||||
|
float(-cmd_vel.twist.linear.z) };
|
||||||
|
const float yaw_rate = -cmd_vel.twist.angular.z;
|
||||||
|
|
||||||
|
auto &ahrs = AP::ahrs();
|
||||||
|
linear_velocity = ahrs.body_to_earth(linear_velocity_base_link);
|
||||||
|
return external_control->set_linear_velocity_and_yaw_rate(linear_velocity, yaw_rate);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Convert commands from ENU to NED frame
|
else if (strcmp(cmd_vel.header.frame_id, MAP_FRAME) == 0) {
|
||||||
Vector3f linear_velocity {
|
// Convert commands from ENU to NED frame
|
||||||
float(cmd_vel.twist.linear.y),
|
Vector3f linear_velocity {
|
||||||
float(cmd_vel.twist.linear.x),
|
float(cmd_vel.twist.linear.y),
|
||||||
float(-cmd_vel.twist.linear.z) };
|
float(cmd_vel.twist.linear.x),
|
||||||
const float yaw_rate = -cmd_vel.twist.angular.z;
|
float(-cmd_vel.twist.linear.z) };
|
||||||
return external_control->set_linear_velocity_and_yaw_rate(linear_velocity, yaw_rate);
|
const float yaw_rate = -cmd_vel.twist.angular.z;
|
||||||
|
return external_control->set_linear_velocity_and_yaw_rate(linear_velocity, yaw_rate);
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue