Path: blob/master/libraries/AP_DDS/AP_DDS_ExternalControl.h
9594 views
#pragma once12#if AP_DDS_ENABLED3#include "ardupilot_msgs/msg/GlobalPosition.h"4#include "geometry_msgs/msg/TwistStamped.h"5#include <AP_Arming/AP_Arming.h>6#include <AP_Common/Location.h>78class AP_DDS_External_Control9{10public:11// REP-147 Goal Interface Global Position Control12// https://ros.org/reps/rep-0147.html#goal-interface13static bool handle_global_position_control(ardupilot_msgs_msg_GlobalPosition& cmd_pos);14static bool handle_velocity_control(geometry_msgs_msg_TwistStamped& cmd_vel);15static bool arm(AP_Arming::Method method, bool do_arming_checks);16static bool disarm(AP_Arming::Method method, bool do_disarm_checks);1718private:19static bool convert_alt_frame(const uint8_t frame_in, Location::AltFrame& frame_out);20};21#endif // AP_DDS_ENABLED222324