Mission manupulation plugin. More...
Public Member Functions | |
const message_map | get_rx_handlers () |
Return map with message rx handlers. | |
void | initialize (UAS &uas_) |
Plugin initializer. | |
WaypointPlugin () | |
Private Types | |
enum | { WP_IDLE, WP_RXLIST, WP_RXWP, WP_TXLIST, WP_TXWP, WP_CLEAR, WP_SET_CUR } |
Private Member Functions | |
bool | clear_cb (mavros_msgs::WaypointClear::Request &req, mavros_msgs::WaypointClear::Response &res) |
void | connection_cb (bool connected) |
void | go_idle (void) |
void | handle_mission_ack (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
void | handle_mission_count (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
void | handle_mission_current (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
void | handle_mission_item (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
void | handle_mission_item_reached (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
void | handle_mission_request (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
void | mission_ack (enum MAV_MISSION_RESULT type) |
void | mission_clear_all () |
void | mission_count (uint16_t cnt) |
void | mission_item (WaypointItem &wp) |
void | mission_request (uint16_t seq) |
void | mission_request_list () |
void | mission_set_current (uint16_t seq) |
void | publish_waypoints () |
bool | pull_cb (mavros_msgs::WaypointPull::Request &req, mavros_msgs::WaypointPull::Response &res) |
bool | push_cb (mavros_msgs::WaypointPush::Request &req, mavros_msgs::WaypointPush::Response &res) |
void | request_mission_done (void) |
void | restart_timeout_timer (void) |
void | restart_timeout_timer_int (void) |
void | send_waypoint (size_t seq) |
bool | set_cur_cb (mavros_msgs::WaypointSetCurrent::Request &req, mavros_msgs::WaypointSetCurrent::Response &res) |
void | set_current_waypoint (size_t seq) |
void | shedule_pull (const ros::Duration &dt) |
void | sheduled_pull_cb (const ros::TimerEvent &event) |
void | timeout_cb (const ros::TimerEvent &event) |
bool | wait_fetch_all () |
bool | wait_push_all () |
Private Attributes | |
const ros::Duration | BOOTUP_TIME_DT |
ros::ServiceServer | clear_srv |
bool | do_pull_after_gcs |
bool | is_timedout |
std::condition_variable | list_receiving |
std::condition_variable | list_sending |
const ros::Duration | LIST_TIMEOUT_DT |
std::recursive_mutex | mutex |
ros::ServiceServer | pull_srv |
ros::ServiceServer | push_srv |
std::mutex | recv_cond_mutex |
const ros::Duration | RESHEDULE_DT |
bool | reshedule_pull |
std::mutex | send_cond_mutex |
std::vector< WaypointItem > | send_waypoints |
ros::ServiceServer | set_cur_srv |
ros::Timer | shedule_timer |
UAS * | uas |
std::vector< WaypointItem > | waypoints |
size_t | wp_count |
size_t | wp_cur_active |
size_t | wp_cur_id |
ros::Publisher | wp_list_pub |
ros::NodeHandle | wp_nh |
size_t | wp_retries |
size_t | wp_set_active |
enum mavplugin::WaypointPlugin:: { ... } | wp_state |
const ros::Duration | WP_TIMEOUT_DT |
ros::Timer | wp_timer |
Static Private Attributes | |
static constexpr int | BOOTUP_TIME_MS = 15000 |
static constexpr int | LIST_TIMEOUT_MS = 30000 |
system startup delay before start pull | |
static constexpr int | RESHEDULE_MS = 5000 |
static constexpr int | RETRIES_COUNT = 3 |
static constexpr int | WP_TIMEOUT_MS = 1000 |
Timeout for pull/push operations. |
Mission manupulation plugin.
Definition at line 137 of file waypoint.cpp.