dwa_local_planner::DWAPlannerROS Class Reference

ROS Wrapper for the DWAPlanner that adheres to the BaseLocalPlanner interface and can be used as a plugin for move_base. More...

#include <dwa_planner_ros.h>

List of all members.

Public Member Functions

bool computeVelocityCommands (geometry_msgs::Twist &cmd_vel)
 Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base.
 DWAPlannerROS ()
 Constructor for DWAPlannerROS wrapper.
void initialize (std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros)
 Constructs the ros wrapper.
bool isGoalReached ()
 Check if the goal pose has been achieved.
bool setPlan (const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
 Set the plan that the controller is following.

Private Member Functions

void odomCallback (const nav_msgs::Odometry::ConstPtr &msg)
 Callback for receiving odometry data.
bool rotateToGoal (const tf::Stamped< tf::Pose > &global_pose, const tf::Stamped< tf::Pose > &robot_vel, double goal_th, geometry_msgs::Twist &cmd_vel)
 Once a goal position is reached... rotate to the goal orientation.
double sign (double x)
bool stopWithAccLimits (const tf::Stamped< tf::Pose > &global_pose, const tf::Stamped< tf::Pose > &robot_vel, geometry_msgs::Twist &cmd_vel)
 Stop the robot taking into account acceleration limits.

Private Attributes

nav_msgs::Odometry base_odom_
costmap_2d::Costmap2DROS * costmap_ros_
boost::shared_ptr< DWAPlannerdp_
ros::Publisher g_plan_pub_
std::vector
< geometry_msgs::PoseStamped > 
global_plan_
bool initialized_
ros::Publisher l_plan_pub_
bool latch_xy_goal_tolerance_
double max_vel_th_
double min_rot_vel_
double min_vel_th_
boost::mutex odom_mutex_
ros::Subscriber odom_sub_
bool prune_plan_
double rot_stopped_vel_
bool rotating_to_goal_
tf::TransformListener * tf_
double trans_stopped_vel_
double xy_goal_tolerance_
bool xy_tolerance_latch_
double yaw_goal_tolerance_

Detailed Description

ROS Wrapper for the DWAPlanner that adheres to the BaseLocalPlanner interface and can be used as a plugin for move_base.

Definition at line 48 of file dwa_planner_ros.h.


Constructor & Destructor Documentation

dwa_local_planner::DWAPlannerROS::DWAPlannerROS (  )  [inline]

Constructor for DWAPlannerROS wrapper.

Definition at line 53 of file dwa_planner_ros.h.


Member Function Documentation

bool dwa_local_planner::DWAPlannerROS::computeVelocityCommands ( geometry_msgs::Twist &  cmd_vel  ) 

Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base.

Parameters:
cmd_vel Will be filled with the velocity command to be passed to the robot base
Returns:
True if a valid trajectory was found, false otherwise

Definition at line 166 of file dwa_planner_ros.cpp.

void dwa_local_planner::DWAPlannerROS::initialize ( std::string  name,
tf::TransformListener *  tf,
costmap_2d::Costmap2DROS *  costmap_ros 
)

Constructs the ros wrapper.

Parameters:
name The name to give this instance of the trajectory planner
tf A pointer to a transform listener
costmap The cost map to use for assigning costs to trajectories

Definition at line 42 of file dwa_planner_ros.cpp.

bool dwa_local_planner::DWAPlannerROS::isGoalReached (  ) 

Check if the goal pose has been achieved.

Returns:
True if achieved, false otherwise

Definition at line 329 of file dwa_planner_ros.cpp.

void dwa_local_planner::DWAPlannerROS::odomCallback ( const nav_msgs::Odometry::ConstPtr &  msg  )  [private]

Callback for receiving odometry data.

Parameters:
msg An Odometry message

Definition at line 84 of file dwa_planner_ros.cpp.

bool dwa_local_planner::DWAPlannerROS::rotateToGoal ( const tf::Stamped< tf::Pose > &  global_pose,
const tf::Stamped< tf::Pose > &  robot_vel,
double  goal_th,
geometry_msgs::Twist &  cmd_vel 
) [private]

Once a goal position is reached... rotate to the goal orientation.

Parameters:
global_pose The pose of the robot in the global frame
robot_vel The velocity of the robot
goal_th The desired th value for the goal
cmd_vel The velocity commands to be filled
Returns:
True if a valid trajectory was found, false otherwise

Definition at line 124 of file dwa_planner_ros.cpp.

bool dwa_local_planner::DWAPlannerROS::setPlan ( const std::vector< geometry_msgs::PoseStamped > &  orig_global_plan  ) 

Set the plan that the controller is following.

Parameters:
orig_global_plan The plan to pass to the controller
Returns:
True if the plan was updated successfully, false otherwise

Definition at line 346 of file dwa_planner_ros.cpp.

double dwa_local_planner::DWAPlannerROS::sign ( double  x  )  [inline, private]

Definition at line 84 of file dwa_planner_ros.h.

bool dwa_local_planner::DWAPlannerROS::stopWithAccLimits ( const tf::Stamped< tf::Pose > &  global_pose,
const tf::Stamped< tf::Pose > &  robot_vel,
geometry_msgs::Twist &  cmd_vel 
) [private]

Stop the robot taking into account acceleration limits.

Parameters:
global_pose The pose of the robot in the global frame
robot_vel The velocity of the robot
cmd_vel The velocity commands to be filled
Returns:
True if a valid trajectory was found, false otherwise

Definition at line 94 of file dwa_planner_ros.cpp.


Member Data Documentation

nav_msgs::Odometry dwa_local_planner::DWAPlannerROS::base_odom_ [private]

Definition at line 122 of file dwa_planner_ros.h.

costmap_2d::Costmap2DROS* dwa_local_planner::DWAPlannerROS::costmap_ros_ [private]

Definition at line 112 of file dwa_planner_ros.h.

boost::shared_ptr<DWAPlanner> dwa_local_planner::DWAPlannerROS::dp_ [private]

Definition at line 123 of file dwa_planner_ros.h.

Definition at line 120 of file dwa_planner_ros.h.

std::vector<geometry_msgs::PoseStamped> dwa_local_planner::DWAPlannerROS::global_plan_ [private]

Definition at line 124 of file dwa_planner_ros.h.

Definition at line 118 of file dwa_planner_ros.h.

Definition at line 120 of file dwa_planner_ros.h.

Definition at line 126 of file dwa_planner_ros.h.

Definition at line 114 of file dwa_planner_ros.h.

Definition at line 114 of file dwa_planner_ros.h.

Definition at line 114 of file dwa_planner_ros.h.

Definition at line 121 of file dwa_planner_ros.h.

Definition at line 119 of file dwa_planner_ros.h.

Definition at line 117 of file dwa_planner_ros.h.

Definition at line 115 of file dwa_planner_ros.h.

Definition at line 125 of file dwa_planner_ros.h.

tf::TransformListener* dwa_local_planner::DWAPlannerROS::tf_ [private]

Definition at line 113 of file dwa_planner_ros.h.

Definition at line 115 of file dwa_planner_ros.h.

Definition at line 116 of file dwa_planner_ros.h.

Definition at line 126 of file dwa_planner_ros.h.

Definition at line 116 of file dwa_planner_ros.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Friends


dwa_local_planner
Author(s): Eitan Marder-Eppstein
autogenerated on Fri Jan 11 10:00:26 2013