Definition at line 69 of file mrpt_reactivenav2d_node.cpp.
◆ ReactiveNav2DNode()
| ReactiveNav2DNode::ReactiveNav2DNode |
( |
int |
argc, |
|
|
char ** |
argv |
|
) |
| |
|
inline |
◆ navigateTo()
| void ReactiveNav2DNode::navigateTo |
( |
const mrpt::math::TPose2D & |
target | ) |
|
|
inline |
◆ onDoNavigation()
◆ onOdometryReceived()
| void ReactiveNav2DNode::onOdometryReceived |
( |
const nav_msgs::Odometry & |
msg | ) |
|
|
inline |
◆ onRosGoalReceived()
| void ReactiveNav2DNode::onRosGoalReceived |
( |
const geometry_msgs::PoseStampedConstPtr & |
trg_ptr | ) |
|
|
inline |
◆ onRosLocalObstacles()
| void ReactiveNav2DNode::onRosLocalObstacles |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
obs | ) |
|
|
inline |
◆ onRosSetRobotShape()
| void ReactiveNav2DNode::onRosSetRobotShape |
( |
const geometry_msgs::Polygon::ConstPtr & |
newShape | ) |
|
|
inline |
◆ onWaypointSeqReceived()
| void ReactiveNav2DNode::onWaypointSeqReceived |
( |
const mrpt_msgs::WaypointSequence & |
wps | ) |
|
|
inline |
◆ updateWaypointSequence()
| void ReactiveNav2DNode::updateWaypointSequence |
( |
const mrpt_msgs::WaypointSequence & |
msg | ) |
|
|
inline |
◆ m_1st_time_init
| bool ReactiveNav2DNode::m_1st_time_init = false |
|
private |
◆ m_auxinit
◆ m_frameid_reference
| std::string ReactiveNav2DNode::m_frameid_reference = "map" |
|
private |
◆ m_frameid_robot
| std::string ReactiveNav2DNode::m_frameid_robot = "base_link" |
|
private |
◆ m_last_obstacles
| CSimplePointsMap ReactiveNav2DNode::m_last_obstacles |
|
private |
◆ m_last_obstacles_cs
| std::mutex ReactiveNav2DNode::m_last_obstacles_cs |
|
private |
◆ m_localn
◆ m_nav_period
| double ReactiveNav2DNode::m_nav_period = 0.1 |
|
private |
◆ m_nh
◆ m_odometry
| mrpt::obs::CObservationOdometry ReactiveNav2DNode::m_odometry |
|
private |
◆ m_odometry_cs
| std::mutex ReactiveNav2DNode::m_odometry_cs |
|
private |
◆ m_plugin_file
| std::string ReactiveNav2DNode::m_plugin_file |
|
private |
◆ m_profiler
| CTimeLogger ReactiveNav2DNode::m_profiler |
|
private |
◆ m_pub_cmd_vel
◆ m_pub_topic_cmd_vel
| std::string ReactiveNav2DNode::m_pub_topic_cmd_vel = "cmd_vel" |
|
private |
◆ m_reactive_if
◆ m_reactive_nav_engine
| CReactiveNavigationSystem ReactiveNav2DNode::m_reactive_nav_engine |
|
private |
◆ m_reactive_nav_engine_cs
| std::mutex ReactiveNav2DNode::m_reactive_nav_engine_cs |
|
private |
◆ m_save_nav_log
| bool ReactiveNav2DNode::m_save_nav_log = false |
|
private |
◆ m_sub_local_obs
◆ m_sub_nav_goal
◆ m_sub_odometry
◆ m_sub_robot_shape
◆ m_sub_topic_local_obstacles
| std::string ReactiveNav2DNode::m_sub_topic_local_obstacles = "local_map_pointcloud" |
|
private |
◆ m_sub_topic_odometry
| std::string ReactiveNav2DNode::m_sub_topic_odometry = "odom" |
|
private |
◆ m_sub_topic_reactive_nav_goal
| std::string ReactiveNav2DNode::m_sub_topic_reactive_nav_goal = "reactive_nav_goal" |
|
private |
◆ m_sub_topic_robot_shape
| std::string ReactiveNav2DNode::m_sub_topic_robot_shape {} |
|
private |
◆ m_sub_topic_wp_seq
| std::string ReactiveNav2DNode::m_sub_topic_wp_seq = "reactive_nav_waypoints" |
|
private |
◆ m_sub_wp_seq
◆ m_target_allowed_distance
| double ReactiveNav2DNode::m_target_allowed_distance = 0.40f |
|
private |
◆ m_tf_buffer
◆ m_tf_listener
◆ m_timer_run_nav
The documentation for this class was generated from the following file: