#include <waypoints_navi.hpp>
Definition at line 32 of file waypoints_navi.hpp.
◆ anonymous enum
◆ anonymous enum
◆ WaypointsGoalNode()
| yocs::WaypointsGoalNode::WaypointsGoalNode |
( |
| ) |
|
◆ ~WaypointsGoalNode()
| yocs::WaypointsGoalNode::~WaypointsGoalNode |
( |
| ) |
|
◆ cancelAllGoals()
| bool yocs::WaypointsGoalNode::cancelAllGoals |
( |
double |
timeout = 2.0 | ) |
|
|
private |
◆ equals() [1/2]
| bool yocs::WaypointsGoalNode::equals |
( |
const geometry_msgs::PoseStamped & |
a, |
|
|
const geometry_msgs::PoseStamped & |
b |
|
) |
| |
|
private |
◆ equals() [2/2]
◆ init()
| bool yocs::WaypointsGoalNode::init |
( |
| ) |
|
◆ navCtrlCB()
| void yocs::WaypointsGoalNode::navCtrlCB |
( |
const yocs_msgs::NavigationControl::ConstPtr & |
nav_ctrl | ) |
|
◆ publishStatusUpdate()
| void yocs::WaypointsGoalNode::publishStatusUpdate |
( |
const uint8_t & |
status | ) |
|
|
private |
◆ resetWaypoints()
| void yocs::WaypointsGoalNode::resetWaypoints |
( |
| ) |
|
|
private |
◆ spin()
| void yocs::WaypointsGoalNode::spin |
( |
| ) |
|
◆ trajectoriesCB()
| void yocs::WaypointsGoalNode::trajectoriesCB |
( |
const yocs_msgs::TrajectoryList::ConstPtr & |
trajs | ) |
|
◆ waypointsCB()
| void yocs::WaypointsGoalNode::waypointsCB |
( |
const yocs_msgs::WaypointList::ConstPtr & |
wps | ) |
|
◆ close_enough_
| double yocs::WaypointsGoalNode::close_enough_ |
|
private |
◆ frequency_
| double yocs::WaypointsGoalNode::frequency_ |
|
private |
◆ goal_
| geometry_msgs::PoseStamped yocs::WaypointsGoalNode::goal_ |
|
private |
◆ goal_timeout_
| double yocs::WaypointsGoalNode::goal_timeout_ |
|
private |
◆ idle_status_update_sent_
| bool yocs::WaypointsGoalNode::idle_status_update_sent_ |
|
private |
◆ mode_
| enum { ... } yocs::WaypointsGoalNode::mode_ |
◆ move_base_ac_
◆ nav_ctrl_sub_
◆ NOWHERE
| const geometry_msgs::PoseStamped yocs::WaypointsGoalNode::NOWHERE |
|
private |
◆ robot_frame_
| std::string yocs::WaypointsGoalNode::robot_frame_ |
|
private |
◆ state_
| enum { ... } yocs::WaypointsGoalNode::state_ |
◆ status_pub_
◆ tf_listener_
◆ traj_list_
| yocs_msgs::TrajectoryList yocs::WaypointsGoalNode::traj_list_ |
|
private |
◆ trajectories_sub_
◆ waypoints_
| std::vector<geometry_msgs::PoseStamped> yocs::WaypointsGoalNode::waypoints_ |
|
private |
◆ waypoints_it_
| std::vector<geometry_msgs::PoseStamped>::iterator yocs::WaypointsGoalNode::waypoints_it_ |
|
private |
◆ waypoints_sub_
◆ world_frame_
| std::string yocs::WaypointsGoalNode::world_frame_ |
|
private |
◆ wp_list_
| yocs_msgs::WaypointList yocs::WaypointsGoalNode::wp_list_ |
|
private |
The documentation for this class was generated from the following files: