Public Member Functions | Private Member Functions | Private Attributes
bipedRobin_local_planner::BipedRobinPlannerROS Class Reference

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

#include <bipedRobin_planner_ros.h>

Inheritance diagram for bipedRobin_local_planner::BipedRobinPlannerROS:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 BipedRobinPlannerROS ()
 Constructor for BipedRobinPlannerROS wrapper.
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.
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.
void stepsLeftCallback (const std_msgs::UInt8 stepsLeftInBuffer)

Private Member Functions

void getFootstepFromState (const footstep_planner::State &from, const footstep_planner::State &to, bipedRobin_msgs::StepTarget3D *footstep)
void goalPoseCallback (const geometry_msgs::PoseStampedConstPtr &goal_pose)
 Callback for receiving odometry data.
bool initializeNavigator ()
void mapCallback (const nav_msgs::OccupancyGridConstPtr &occupancy_map)
 Callback to set the map.
void planningThread (void)
double sign (double x)
void updateMapToPlanner ()

Private Attributes

costmap_2d::Costmap2DROScostmap_ros_
ros::Publisher g_plan_pub_
std::vector
< geometry_msgs::PoseStamped > 
global_plan_
bool initialized_
ros::ServiceClient ivFootstepIncSrv
boost::mutex ivFootstepPlanningMutex
boost::thread * ivFootstepPlanningThread
ros::ServiceServer ivFootstepPlanService
std::string ivIdFootLeft
std::string ivIdFootRight
std::string ivIdMapFrame
footstep_planner::State ivLeftLegCurrent
footstep_planner::State ivLeftLegStart
double ivLocalGoalTheta
double ivLocalGoalX
double ivLocalGoalY
ros::Publisher ivMapPub
footstep_planner::FootstepPlanner ivPlanner
double ivPlanningDistance
bool ivPlanSteps
footstep_planner::State ivRightLegCurrent
footstep_planner::State ivRightLegStart
int ivSendStep
std::list
< footstep_planner::State
ivStepsToStart
ros::Publisher l_plan_pub_
boost::mutex localPlan_mutex_
double max_vel_th_
double min_rot_vel_
double min_vel_th_
boost::mutex planner_mutex_
bool prune_plan_
double rot_stopped_vel_
ros::Subscriber stepsLeftInBufferSub
tf::TransformListenertf_
double trans_stopped_vel_
double xy_goal_tolerance_
double yaw_goal_tolerance_

Detailed Description

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

Definition at line 17 of file bipedRobin_planner_ros.h.


Constructor & Destructor Documentation

Constructor for BipedRobinPlannerROS wrapper.

Definition at line 22 of file bipedRobin_planner_ros.h.


Member Function Documentation

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 49 of file bipedRobin_planner_ros.cpp.

Definition at line 193 of file bipedRobin_planner_ros.cpp.

void bipedRobin_local_planner::BipedRobinPlannerROS::goalPoseCallback ( const geometry_msgs::PoseStampedConstPtr &  goal_pose) [private]

Callback for receiving odometry data.

Parameters:
msgAn Odometry message Callback to set a simulated robot at a certain pose.

Subscribed to 'goal'.

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

Constructs the ros wrapper.

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 14 of file bipedRobin_planner_ros.cpp.

Definition at line 266 of file bipedRobin_planner_ros.cpp.

Check if the goal pose has been achieved.

Returns:
True if achieved, false otherwise

Implements nav_core::BaseLocalPlanner.

Definition at line 170 of file bipedRobin_planner_ros.cpp.

void bipedRobin_local_planner::BipedRobinPlannerROS::mapCallback ( const nav_msgs::OccupancyGridConstPtr &  occupancy_map) [private]

Callback to set the map.

Subscribed to 'map'.

Definition at line 303 of file bipedRobin_planner_ros.cpp.

bool bipedRobin_local_planner::BipedRobinPlannerROS::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 219 of file bipedRobin_planner_ros.cpp.

double bipedRobin_local_planner::BipedRobinPlannerROS::sign ( double  x) [inline, private]

Definition at line 55 of file bipedRobin_planner_ros.h.

void bipedRobin_local_planner::BipedRobinPlannerROS::stepsLeftCallback ( const std_msgs::UInt8  stepsLeftInBuffer)

Definition at line 185 of file bipedRobin_planner_ros.cpp.

Definition at line 234 of file bipedRobin_planner_ros.cpp.


Member Data Documentation

Definition at line 85 of file bipedRobin_planner_ros.h.

Definition at line 95 of file bipedRobin_planner_ros.h.

Definition at line 122 of file bipedRobin_planner_ros.h.

Definition at line 91 of file bipedRobin_planner_ros.h.

Definition at line 97 of file bipedRobin_planner_ros.h.

Definition at line 104 of file bipedRobin_planner_ros.h.

Definition at line 103 of file bipedRobin_planner_ros.h.

Definition at line 102 of file bipedRobin_planner_ros.h.

Definition at line 109 of file bipedRobin_planner_ros.h.

Definition at line 108 of file bipedRobin_planner_ros.h.

Definition at line 110 of file bipedRobin_planner_ros.h.

Definition at line 116 of file bipedRobin_planner_ros.h.

Definition at line 114 of file bipedRobin_planner_ros.h.

Definition at line 120 of file bipedRobin_planner_ros.h.

Definition at line 118 of file bipedRobin_planner_ros.h.

Definition at line 119 of file bipedRobin_planner_ros.h.

Definition at line 96 of file bipedRobin_planner_ros.h.

Definition at line 100 of file bipedRobin_planner_ros.h.

Definition at line 111 of file bipedRobin_planner_ros.h.

Definition at line 93 of file bipedRobin_planner_ros.h.

Definition at line 117 of file bipedRobin_planner_ros.h.

Definition at line 115 of file bipedRobin_planner_ros.h.

Definition at line 92 of file bipedRobin_planner_ros.h.

Definition at line 113 of file bipedRobin_planner_ros.h.

Definition at line 95 of file bipedRobin_planner_ros.h.

Definition at line 106 of file bipedRobin_planner_ros.h.

Definition at line 87 of file bipedRobin_planner_ros.h.

Definition at line 87 of file bipedRobin_planner_ros.h.

Definition at line 87 of file bipedRobin_planner_ros.h.

Definition at line 105 of file bipedRobin_planner_ros.h.

Definition at line 90 of file bipedRobin_planner_ros.h.

Definition at line 88 of file bipedRobin_planner_ros.h.

Definition at line 98 of file bipedRobin_planner_ros.h.

Definition at line 86 of file bipedRobin_planner_ros.h.

Definition at line 88 of file bipedRobin_planner_ros.h.

Definition at line 89 of file bipedRobin_planner_ros.h.

Definition at line 89 of file bipedRobin_planner_ros.h.


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


bipedRobin_local_planner
Author(s): Johannes Mayr
autogenerated on Fri Nov 15 2013 11:11:17