Command plugin. More...
Public Member Functions | |
CommandPlugin () | |
std::string const | get_name () const |
Plugin name (CamelCase) | |
const message_map | get_rx_handlers () |
Return map with message rx handlers. | |
void | initialize (UAS &uas_, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater) |
Plugin initializer. | |
Private Member Functions | |
bool | arming_cb (mavros::CommandBool::Request &req, mavros::CommandBool::Response &res) |
void | command_int (uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) |
bool | command_int_cb (mavros::CommandInt::Request &req, mavros::CommandInt::Response &res) |
void | command_long (uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) |
bool | command_long_cb (mavros::CommandLong::Request &req, mavros::CommandLong::Response &res) |
bool | guided_cb (mavros::CommandBool::Request &req, mavros::CommandBool::Response &res) |
void | handle_command_ack (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
bool | land_cb (mavros::CommandTOL::Request &req, mavros::CommandTOL::Response &res) |
bool | send_command_int (uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z, unsigned char &success) |
bool | send_command_long_and_wait (uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, unsigned char &success, uint8_t &result) |
bool | set_home_cb (mavros::CommandHome::Request &req, mavros::CommandHome::Response &res) |
bool | takeoff_cb (mavros::CommandTOL::Request &req, mavros::CommandTOL::Response &res) |
bool | wait_ack_for (CommandTransaction *tr) |
Private Attributes | |
const ros::Duration | ACK_TIMEOUT_DT |
std::list< CommandTransaction * > | ack_waiting_list |
ros::ServiceServer | arming_srv |
ros::NodeHandle | cmd_nh |
ros::ServiceServer | command_int_srv |
ros::ServiceServer | command_long_srv |
ros::ServiceServer | guided_srv |
ros::ServiceServer | land_srv |
std::recursive_mutex | mutex |
ros::ServiceServer | set_home_srv |
ros::ServiceServer | takeoff_srv |
UAS * | uas |
Static Private Attributes | |
static constexpr int | ACK_TIMEOUT_MS = 5000 |