Public Member Functions | Private Member Functions | Private Attributes
dt_local_planner::DTPlannerROS Class Reference

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

#include <dt_planner_ros.h>

Inheritance diagram for dt_local_planner::DTPlannerROS:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual 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.
 DTPlannerROS ()
 Constructor for DTPlannerROS.
virtual void initialize (std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros)
 Constructs the planner.
virtual bool isGoalReached ()
 Check if the goal pose has been achieved.
virtual bool setPlan (const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
 Set the plan that the controller is following.
virtual ~DTPlannerROS ()
 Destructor for the planner.

Private Member Functions

bool isInitialized ()
void reconfigureCB (DTPlannerConfig &config, uint32_t level)
 Callback to update the local planner's parameters based on dynamic reconfigure.

Private Attributes

std::vector< double > aCoeff_x_
std::vector< double > aCoeff_y_
costmap_2d::Costmap2DROScostmap_ros_
dynamic_reconfigure::Server
< DTPlannerConfig > * 
dsrv_
bool firstComputeVelocityCommands_
ros::Publisher g_plan_pub_
double gamma_dest0_
bool goal_reached_
double goal_x_
double goal_y_
bool initialized_
double K_d_
double K_p_
ros::Publisher l_plan_pub_
double lastCall_time_
double max_ang_
double max_vel_
double max_vel_deltaT0_
bool move_
int nPolyGrad_
base_local_planner::OdometryHelperRos odom_helper_
std::vector
< geometry_msgs::PoseStamped > 
plan_
int planSize_
double start_time_
int stepCnt_max_vel_
tf::TransformListenertf_
 Used for transforming point clouds.
double vel_dest0_

Detailed Description

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

Definition at line 67 of file dt_planner_ros.h.


Constructor & Destructor Documentation

Constructor for DTPlannerROS.

Definition at line 64 of file dt_planner_ros.cpp.

Destructor for the planner.

Definition at line 168 of file dt_planner_ros.cpp.


Member Function Documentation

bool dt_local_planner::DTPlannerROS::computeVelocityCommands ( geometry_msgs::Twist &  cmd_vel) [virtual]

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

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

Implements nav_core::BaseLocalPlanner.

Definition at line 173 of file dt_planner_ros.cpp.

void dt_local_planner::DTPlannerROS::initialize ( std::string  name,
tf::TransformListener tf,
costmap_2d::Costmap2DROS costmap_ros 
) [virtual]

Constructs the planner.

Parameters:
nameThe name to give this instance of the trajectory planner
tfA pointer to a transform listener
costmapThe cost map to use for assigning costs to trajectories

Implements nav_core::BaseLocalPlanner.

Definition at line 68 of file dt_planner_ros.cpp.

Check if the goal pose has been achieved.

Returns:
True if achieved, false otherwise

Implements nav_core::BaseLocalPlanner.

Definition at line 160 of file dt_planner_ros.cpp.

Definition at line 110 of file dt_planner_ros.h.

void dt_local_planner::DTPlannerROS::reconfigureCB ( DTPlannerConfig &  config,
uint32_t  level 
) [private]

Callback to update the local planner's parameters based on dynamic reconfigure.

Definition at line 53 of file dt_planner_ros.cpp.

bool dt_local_planner::DTPlannerROS::setPlan ( const std::vector< geometry_msgs::PoseStamped > &  orig_global_plan) [virtual]

Set the plan that the controller is following.

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

Implements nav_core::BaseLocalPlanner.

Definition at line 96 of file dt_planner_ros.cpp.


Member Data Documentation

std::vector<double> dt_local_planner::DTPlannerROS::aCoeff_x_ [private]

Definition at line 137 of file dt_planner_ros.h.

std::vector<double> dt_local_planner::DTPlannerROS::aCoeff_y_ [private]

Definition at line 138 of file dt_planner_ros.h.

Definition at line 124 of file dt_planner_ros.h.

dynamic_reconfigure::Server<DTPlannerConfig>* dt_local_planner::DTPlannerROS::dsrv_ [private]

Definition at line 127 of file dt_planner_ros.h.

Definition at line 160 of file dt_planner_ros.h.

Definition at line 122 of file dt_planner_ros.h.

Definition at line 145 of file dt_planner_ros.h.

Definition at line 164 of file dt_planner_ros.h.

Definition at line 134 of file dt_planner_ros.h.

Definition at line 135 of file dt_planner_ros.h.

Definition at line 129 of file dt_planner_ros.h.

Definition at line 149 of file dt_planner_ros.h.

Definition at line 148 of file dt_planner_ros.h.

Definition at line 122 of file dt_planner_ros.h.

Definition at line 143 of file dt_planner_ros.h.

Definition at line 153 of file dt_planner_ros.h.

Definition at line 152 of file dt_planner_ros.h.

Definition at line 154 of file dt_planner_ros.h.

Definition at line 159 of file dt_planner_ros.h.

Definition at line 140 of file dt_planner_ros.h.

Definition at line 131 of file dt_planner_ros.h.

std::vector<geometry_msgs::PoseStamped> dt_local_planner::DTPlannerROS::plan_ [private]

Definition at line 133 of file dt_planner_ros.h.

Definition at line 141 of file dt_planner_ros.h.

Definition at line 142 of file dt_planner_ros.h.

Definition at line 155 of file dt_planner_ros.h.

Used for transforming point clouds.

Definition at line 119 of file dt_planner_ros.h.

Definition at line 144 of file dt_planner_ros.h.


The documentation for this class was generated from the following files:


dt_local_planner
Author(s): Stephan Hofstaetter
autogenerated on Fri Aug 28 2015 13:41:25