2023-08-08 21:41:46 -03:00
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#if AP_DDS_ENABLED
|
2023-12-07 02:49:01 -04:00
|
|
|
#include "ardupilot_msgs/msg/GlobalPosition.h"
|
2023-08-08 21:41:46 -03:00
|
|
|
#include "geometry_msgs/msg/TwistStamped.h"
|
|
|
|
|
2023-12-07 02:49:01 -04:00
|
|
|
#include <AP_Common/Location.h>
|
|
|
|
|
2023-08-08 21:41:46 -03:00
|
|
|
class AP_DDS_External_Control
|
|
|
|
{
|
|
|
|
public:
|
2023-12-07 02:49:01 -04:00
|
|
|
// REP-147 Goal Interface Global Position Control
|
|
|
|
// https://ros.org/reps/rep-0147.html#goal-interface
|
|
|
|
static bool handle_global_position_control(ardupilot_msgs_msg_GlobalPosition& cmd_pos);
|
2023-08-08 21:41:46 -03:00
|
|
|
static bool handle_velocity_control(geometry_msgs_msg_TwistStamped& cmd_vel);
|
2023-12-07 02:49:01 -04:00
|
|
|
private:
|
|
|
|
static bool convert_alt_frame(const uint8_t frame_in, Location::AltFrame& frame_out);
|
2023-08-08 21:41:46 -03:00
|
|
|
};
|
|
|
|
#endif // AP_DDS_ENABLED
|