Skip to content

Commit

Permalink
AP_DDS: Split external control to its own file
Browse files Browse the repository at this point in the history
* Improves encapsulation, separates concerns

Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
  • Loading branch information
Ryanf55 committed Aug 16, 2023
1 parent f440e74 commit 3cf9f7f
Show file tree
Hide file tree
Showing 3 changed files with 37 additions and 14 deletions.
16 changes: 2 additions & 14 deletions libraries/AP_DDS/AP_DDS_Client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
#include <AP_Arming/AP_Arming.h>
#include <AP_ExternalControl/AP_ExternalControl_config.h>
#if AP_EXTERNAL_CONTROL_ENABLED
#include <AP_ExternalControl/AP_ExternalControl.h>
#include "AP_DDS_ExternalControl.h"
#endif

#include "AP_DDS_Client.h"
Expand Down Expand Up @@ -480,19 +480,7 @@ void AP_DDS_Client::on_topic(uxrSession* uxr_session, uxrObjectId object_id, uin

subscribe_sample_count++;
#if AP_EXTERNAL_CONTROL_ENABLED
auto *external_control = AP::externalcontrol();
if (external_control == nullptr) {
break;
}
/*
get commands from ENU to NED frame
*/
Vector3f linear_velocity {
float(rx_velocity_control_topic.twist.linear.y),
float(rx_velocity_control_topic.twist.linear.x),
float(-rx_velocity_control_topic.twist.linear.z) };
const float yaw_rate = -rx_velocity_control_topic.twist.angular.z;
if (!external_control->set_linear_velocity_and_yaw_rate(linear_velocity, yaw_rate)) {
if (!AP_DDS_External_Control::handle_velocity_control(rx_velocity_control_topic)) {
// TODO #23430 handle velocity control failure through rosout, throttled.
}
#endif // AP_EXTERNAL_CONTROL_ENABLED
Expand Down
24 changes: 24 additions & 0 deletions libraries/AP_DDS/AP_DDS_ExternalControl.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
#if AP_DDS_ENABLED

#include "AP_DDS_ExternalControl.h"

#include <AP_ExternalControl/AP_ExternalControl.h>

bool AP_DDS_External_Control::handle_velocity_control(geometry_msgs_msg_TwistStamped& cmd_vel)
{
auto *external_control = AP::externalcontrol();
if (external_control == nullptr) {
return false;
}

// Convert commands from ENU to NED frame
Vector3f linear_velocity {
float(cmd_vel.twist.linear.y),
float(cmd_vel.twist.linear.x),
float(-cmd_vel.twist.linear.z) };
const float yaw_rate = -cmd_vel.twist.angular.z;
return external_control->set_linear_velocity_and_yaw_rate(linear_velocity, yaw_rate);
}


#endif // AP_DDS_ENABLED
11 changes: 11 additions & 0 deletions libraries/AP_DDS/AP_DDS_ExternalControl.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
#pragma once

#if AP_DDS_ENABLED
#include "geometry_msgs/msg/TwistStamped.h"

class AP_DDS_External_Control
{
public:
static bool handle_velocity_control(geometry_msgs_msg_TwistStamped& cmd_vel);
};
#endif // AP_DDS_ENABLED

0 comments on commit 3cf9f7f

Please sign in to comment.