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>
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 for BipedRobinPlannerROS wrapper.
Definition at line 22 of file bipedRobin_planner_ros.h.
bool bipedRobin_local_planner::BipedRobinPlannerROS::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.
cmd_vel | Will be filled with the velocity command to be passed to the robot base |
Implements nav_core::BaseLocalPlanner.
Definition at line 49 of file bipedRobin_planner_ros.cpp.
void bipedRobin_local_planner::BipedRobinPlannerROS::getFootstepFromState | ( | const footstep_planner::State & | from, |
const footstep_planner::State & | to, | ||
bipedRobin_msgs::StepTarget3D * | footstep | ||
) | [private] |
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.
msg | An 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.
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 |
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.
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'.
void bipedRobin_local_planner::BipedRobinPlannerROS::planningThread | ( | void | ) | [private] |
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.
orig_global_plan | The plan to pass to the controller |
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.
void bipedRobin_local_planner::BipedRobinPlannerROS::updateMapToPlanner | ( | ) | [private] |
Definition at line 234 of file bipedRobin_planner_ros.cpp.
Definition at line 85 of file bipedRobin_planner_ros.h.
Definition at line 95 of file bipedRobin_planner_ros.h.
std::vector<geometry_msgs::PoseStamped> bipedRobin_local_planner::BipedRobinPlannerROS::global_plan_ [private] |
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.
boost::mutex bipedRobin_local_planner::BipedRobinPlannerROS::ivFootstepPlanningMutex [private] |
Definition at line 104 of file bipedRobin_planner_ros.h.
boost::thread* bipedRobin_local_planner::BipedRobinPlannerROS::ivFootstepPlanningThread [private] |
Definition at line 103 of file bipedRobin_planner_ros.h.
Definition at line 102 of file bipedRobin_planner_ros.h.
std::string bipedRobin_local_planner::BipedRobinPlannerROS::ivIdFootLeft [private] |
Definition at line 109 of file bipedRobin_planner_ros.h.
std::string bipedRobin_local_planner::BipedRobinPlannerROS::ivIdFootRight [private] |
Definition at line 108 of file bipedRobin_planner_ros.h.
std::string bipedRobin_local_planner::BipedRobinPlannerROS::ivIdMapFrame [private] |
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.
double bipedRobin_local_planner::BipedRobinPlannerROS::ivLocalGoalTheta [private] |
Definition at line 120 of file bipedRobin_planner_ros.h.
double bipedRobin_local_planner::BipedRobinPlannerROS::ivLocalGoalX [private] |
Definition at line 118 of file bipedRobin_planner_ros.h.
double bipedRobin_local_planner::BipedRobinPlannerROS::ivLocalGoalY [private] |
Definition at line 119 of file bipedRobin_planner_ros.h.
Definition at line 96 of file bipedRobin_planner_ros.h.
footstep_planner::FootstepPlanner bipedRobin_local_planner::BipedRobinPlannerROS::ivPlanner [private] |
Definition at line 100 of file bipedRobin_planner_ros.h.
double bipedRobin_local_planner::BipedRobinPlannerROS::ivPlanningDistance [private] |
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.
std::list<footstep_planner::State> bipedRobin_local_planner::BipedRobinPlannerROS::ivStepsToStart [private] |
Definition at line 113 of file bipedRobin_planner_ros.h.
Definition at line 95 of file bipedRobin_planner_ros.h.
boost::mutex bipedRobin_local_planner::BipedRobinPlannerROS::localPlan_mutex_ [private] |
Definition at line 106 of file bipedRobin_planner_ros.h.
double bipedRobin_local_planner::BipedRobinPlannerROS::max_vel_th_ [private] |
Definition at line 87 of file bipedRobin_planner_ros.h.
double bipedRobin_local_planner::BipedRobinPlannerROS::min_rot_vel_ [private] |
Definition at line 87 of file bipedRobin_planner_ros.h.
double bipedRobin_local_planner::BipedRobinPlannerROS::min_vel_th_ [private] |
Definition at line 87 of file bipedRobin_planner_ros.h.
boost::mutex bipedRobin_local_planner::BipedRobinPlannerROS::planner_mutex_ [private] |
Definition at line 105 of file bipedRobin_planner_ros.h.
Definition at line 90 of file bipedRobin_planner_ros.h.
double bipedRobin_local_planner::BipedRobinPlannerROS::rot_stopped_vel_ [private] |
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.
double bipedRobin_local_planner::BipedRobinPlannerROS::trans_stopped_vel_ [private] |
Definition at line 88 of file bipedRobin_planner_ros.h.
double bipedRobin_local_planner::BipedRobinPlannerROS::xy_goal_tolerance_ [private] |
Definition at line 89 of file bipedRobin_planner_ros.h.
double bipedRobin_local_planner::BipedRobinPlannerROS::yaw_goal_tolerance_ [private] |
Definition at line 89 of file bipedRobin_planner_ros.h.