$search
#include <cart_local_planner.h>
Definition at line 81 of file cart_local_planner.h.
enum cart_local_planner::CartLocalPlanner::CONTROL_MODE [protected] |
Reimplemented in cart_local_planner::FixedFrontCartPlanner, and cart_local_planner::HolonomicCartPlanner.
Definition at line 204 of file cart_local_planner.h.
enum cart_local_planner::CartLocalPlanner::FILTER_OPTIONS [protected] |
Reimplemented in cart_local_planner::FixedFrontCartPlanner, and cart_local_planner::HolonomicCartPlanner.
Definition at line 198 of file cart_local_planner.h.
cart_local_planner::CartLocalPlanner::CartLocalPlanner | ( | ) |
Definition at line 135 of file cart_local_planner.cpp.
double cart_local_planner::CartLocalPlanner::baseTwistFromError | ( | ) | [protected] |
* Sets twist_base_ based on robot_pose_error_, returns twist magnitude
Definition at line 782 of file cart_local_planner.cpp.
double cart_local_planner::CartLocalPlanner::cartTwistFromError | ( | ) | [protected] |
* Sets twist_cart_ based on cart_pose_error_, returns twist magnitutde
Definition at line 791 of file cart_local_planner.cpp.
bool cart_local_planner::CartLocalPlanner::checkTrajectoryMonotonic | ( | const std::vector< unsigned int > & | indices | ) | [protected] |
Definition at line 430 of file cart_local_planner.cpp.
bool cart_local_planner::CartLocalPlanner::checkTwists | ( | ) | [protected, virtual] |
Check twists for collision in costmap
Definition at line 655 of file cart_local_planner.cpp.
bool cart_local_planner::CartLocalPlanner::checkTwistsMonotonic | ( | ) | [protected, virtual] |
Check twists for collision in costmap
Definition at line 689 of file cart_local_planner.cpp.
bool cart_local_planner::CartLocalPlanner::clearCartFootprint | ( | ) | [protected, virtual] |
Definition at line 245 of file cart_local_planner.cpp.
bool cart_local_planner::CartLocalPlanner::computeVelocityCommands | ( | geometry_msgs::Twist & | cmd_vel | ) |
Get the current pose of the robot in the fixed frame
Get the current pose of the cart in the base frame
Save member copies of cart and robot states (the slow way, because TF is annoying)
Alias cmd_vel with our local reference
Set goals for the robot and cart given the current state
Set a control mode based on current state
Generate controls for current control mode
Check final twists before returning
Definition at line 302 of file cart_local_planner.cpp.
void cart_local_planner::CartLocalPlanner::controlModeAction | ( | ) | [protected, virtual] |
Implements what to do during computeVelocityCommands for each control mode. This provides a greater degree of control than the default supported by the base_local_planner API, for problems such as rotating in place or evading collisions that the global planner doesn't know about (e.g. cart collisions).
Reimplemented in cart_local_planner::FixedFrontCartPlanner, and cart_local_planner::HolonomicCartPlanner.
Definition at line 535 of file cart_local_planner.cpp.
void cart_local_planner::CartLocalPlanner::filterTwistsCombined | ( | int | filter_options | ) | [protected, virtual] |
Applies requested operations on the robot and cart twists
filter_options | An int containing OR'ed together FILTER_OPTIONS |
1: Scale everything by its max;
2: Scale base vel based on cart error (turns out to be a very handy trick for keeping the cart on track - this is basically a gaussian)
Reimplemented in cart_local_planner::FixedFrontCartPlanner, and cart_local_planner::HolonomicCartPlanner.
Definition at line 608 of file cart_local_planner.cpp.
void cart_local_planner::CartLocalPlanner::freeze | ( | ) | [protected] |
* set zero twist to arms and base */
Definition at line 930 of file cart_local_planner.cpp.
bool cart_local_planner::CartLocalPlanner::getNextFewWaypointsIndices | ( | const std::vector< geometry_msgs::PoseStamped > & | current_plan, | |
const int & | current_waypoint_index, | |||
const int & | max_num_waypoints, | |||
const double & | max_translation, | |||
const double & | max_rotation, | |||
std::vector< unsigned int > & | waypoint_indices | |||
) | [protected] |
Definition at line 480 of file cart_local_planner.cpp.
void cart_local_planner::CartLocalPlanner::initialization_extras | ( | ) | [protected, virtual] |
A place to implement any additional initialization required for the planner. Gets called at the end of initialize().
Reimplemented in cart_local_planner::FixedFrontCartPlanner, and cart_local_planner::HolonomicCartPlanner.
Definition at line 241 of file cart_local_planner.cpp.
void cart_local_planner::CartLocalPlanner::initialize | ( | std::string | name, | |
tf::TransformListener * | tf, | |||
costmap_2d::Costmap2DROS * | costmap_ros | |||
) | [virtual] |
Implements nav_core::BaseLocalPlanner.
Definition at line 147 of file cart_local_planner.cpp.
void cart_local_planner::CartLocalPlanner::invalidPoseCallback | ( | const std_msgs::Empty::ConstPtr & | msg | ) | [protected] |
* callback for invalid pose notification */
Definition at line 998 of file cart_local_planner.cpp.
bool cart_local_planner::CartLocalPlanner::isGoalReached | ( | ) | [virtual] |
Implements nav_core::BaseLocalPlanner.
Definition at line 1004 of file cart_local_planner.cpp.
gm::Twist cart_local_planner::CartLocalPlanner::mapBaseTwistToCart | ( | const geometry_msgs::Twist & | twist_base | ) | [protected] |
* map twist_base to cart frame, thanks to KDL's frame*twist operator */
Definition at line 950 of file cart_local_planner.cpp.
void cart_local_planner::CartLocalPlanner::odomCallback | ( | const nav_msgs::Odometry::ConstPtr & | msg | ) | [protected] |
* callback for base controller odometry */
Definition at line 990 of file cart_local_planner.cpp.
void cart_local_planner::CartLocalPlanner::publishDebugPose | ( | tf::Pose & | p | ) | [protected] |
Definition at line 982 of file cart_local_planner.cpp.
void cart_local_planner::CartLocalPlanner::publishDebugPose | ( | geometry_msgs::Pose & | p | ) | [protected] |
Definition at line 965 of file cart_local_planner.cpp.
void cart_local_planner::CartLocalPlanner::publishDebugTwist | ( | geometry_msgs::Twist & | t | ) | [protected] |
Definition at line 974 of file cart_local_planner.cpp.
void cart_local_planner::CartLocalPlanner::scaleTwist2D | ( | geometry_msgs::Twist & | t, | |
double | scale | |||
) | [static, protected] |
* scale twist by constant factor */
Definition at line 943 of file cart_local_planner.cpp.
int cart_local_planner::CartLocalPlanner::setCartGoalFromWaypoint | ( | double | min_dist, | |
double | min_x_component | |||
) | [protected] |
Picks a future waypoint on the global plan for the cart based on the distance from the robot
min_dist | The minimum distance a future waypoint must be in order to qualify as a cart goal pose | |
min_x_component | The amount of min_dist that must be in the X direction |
Definition at line 731 of file cart_local_planner.cpp.
void cart_local_planner::CartLocalPlanner::setCartPoseGoal | ( | const tf::Stamped< tf::Pose > & | goal | ) | [protected] |
Definition at line 520 of file cart_local_planner.cpp.
void cart_local_planner::CartLocalPlanner::setControlMode | ( | ) | [protected, virtual] |
Sets the internal control mode for the computeVelocityCommands switch based on the current state of the robot and the cart.
Reimplemented in cart_local_planner::FixedFrontCartPlanner, and cart_local_planner::HolonomicCartPlanner.
Definition at line 530 of file cart_local_planner.cpp.
bool cart_local_planner::CartLocalPlanner::setGoalPoses | ( | ) | [protected, virtual] |
Sets goal poses for the cart and the robot given current state and way-point
Definition at line 561 of file cart_local_planner.cpp.
bool cart_local_planner::CartLocalPlanner::setPlan | ( | const std::vector< geometry_msgs::PoseStamped > & | global_plan | ) | [virtual] |
Implements nav_core::BaseLocalPlanner.
void cart_local_planner::CartLocalPlanner::setRobotPoseGoal | ( | const tf::Stamped< tf::Pose > & | goal | ) | [protected] |
Definition at line 514 of file cart_local_planner.cpp.
void cart_local_planner::CartLocalPlanner::setYawFromVec | ( | const tf::Pose & | pose1, | |
const tf::Pose & | pose2, | |||
tf::Pose & | res | |||
) | [protected] |
* makes a new pose with yaw set from xy coordinate deltas (atan) */
Definition at line 803 of file cart_local_planner.cpp.
vector< gm::Point > cart_local_planner::CartLocalPlanner::transformFootprint | ( | const geometry_msgs::PolygonStamped & | poly | ) | const [protected] |
* converts poly to footprint in the costmap global frame */
Definition at line 912 of file cart_local_planner.cpp.
bool cart_local_planner::CartLocalPlanner::transformGlobalPlan | ( | const tf::TransformListener & | tf, | |
const std::vector< geometry_msgs::PoseStamped > & | global_plan, | |||
const costmap_2d::Costmap2DROS & | costmap, | |||
const std::string & | global_frame, | |||
std::vector< geometry_msgs::PoseStamped > & | transformed_plan | |||
) | [protected] |
* Transforms global_plan to plan in global frame, and does pruning */
Definition at line 222 of file cart_local_planner.h.
Definition at line 258 of file cart_local_planner.h.
Definition at line 218 of file cart_local_planner.h.
double cart_local_planner::CartLocalPlanner::cart_length_ [protected] |
Definition at line 255 of file cart_local_planner.h.
Cart pose in robot frame
Definition at line 229 of file cart_local_planner.h.
Distance from actual cart pose to goal pose
Definition at line 237 of file cart_local_planner.h.
Cart pose in robot frame
Definition at line 233 of file cart_local_planner.h.
Publisher for controlling cart position
Definition at line 261 of file cart_local_planner.h.
Definition at line 265 of file cart_local_planner.h.
Publisher for controlling cart velocity
Definition at line 262 of file cart_local_planner.h.
double cart_local_planner::CartLocalPlanner::cart_width_ [protected] |
Definition at line 255 of file cart_local_planner.h.
double cart_local_planner::CartLocalPlanner::cart_x_offset_ [protected] |
Definition at line 255 of file cart_local_planner.h.
double cart_local_planner::CartLocalPlanner::cart_y_offset_ [protected] |
Definition at line 255 of file cart_local_planner.h.
bool cart_local_planner::CartLocalPlanner::cleared_cart_footprint_ [protected] |
Definition at line 256 of file cart_local_planner.h.
enum CONTROL_MODE cart_local_planner::CartLocalPlanner::control_mode_ [protected] |
Reimplemented in cart_local_planner::FixedFrontCartPlanner, and cart_local_planner::HolonomicCartPlanner.
Definition at line 209 of file cart_local_planner.h.
Definition at line 215 of file cart_local_planner.h.
unsigned int cart_local_planner::CartLocalPlanner::current_waypoint_ [protected] |
Waypoint counter
Definition at line 248 of file cart_local_planner.h.
bool cart_local_planner::CartLocalPlanner::debug_print_ [protected] |
Definition at line 271 of file cart_local_planner.h.
double cart_local_planner::CartLocalPlanner::dt_ [protected] |
Trajectory sample time-interval
Definition at line 247 of file cart_local_planner.h.
std::vector<geometry_msgs::PoseStamped> cart_local_planner::CartLocalPlanner::global_plan_ [protected] |
Definition at line 224 of file cart_local_planner.h.
Definition at line 223 of file cart_local_planner.h.
bool cart_local_planner::CartLocalPlanner::initialized_ [protected] |
Definition at line 243 of file cart_local_planner.h.
boost::mutex cart_local_planner::CartLocalPlanner::invalid_pose_mutex_ [protected] |
Definition at line 225 of file cart_local_planner.h.
Definition at line 221 of file cart_local_planner.h.
double cart_local_planner::CartLocalPlanner::K_rot_base_ [protected] |
P-gains for the base
Definition at line 244 of file cart_local_planner.h.
double cart_local_planner::CartLocalPlanner::K_rot_cart_ [protected] |
P-gains for the cart
Definition at line 245 of file cart_local_planner.h.
double cart_local_planner::CartLocalPlanner::K_trans_base_ [protected] |
Definition at line 244 of file cart_local_planner.h.
double cart_local_planner::CartLocalPlanner::K_trans_cart_ [protected] |
Definition at line 245 of file cart_local_planner.h.
Definition at line 275 of file cart_local_planner.h.
Definition at line 213 of file cart_local_planner.h.
int cart_local_planner::CartLocalPlanner::num_traj_steps_ [protected] |
Trajectory length
Definition at line 246 of file cart_local_planner.h.
boost::mutex cart_local_planner::CartLocalPlanner::odom_lock_ [protected] |
Definition at line 225 of file cart_local_planner.h.
Definition at line 221 of file cart_local_planner.h.
std::vector<geometry_msgs::PoseStamped> cart_local_planner::CartLocalPlanner::original_global_plan_ [protected] |
Definition at line 278 of file cart_local_planner.h.
Definition at line 267 of file cart_local_planner.h.
Definition at line 217 of file cart_local_planner.h.
Robot pose in fixed frame
Definition at line 228 of file cart_local_planner.h.
Robot goal pose in current robot frame
Definition at line 236 of file cart_local_planner.h.
Robot pose in fixed frame
Definition at line 232 of file cart_local_planner.h.
double cart_local_planner::CartLocalPlanner::rot_stopped_velocity_ [protected] |
Used to check if base is stopped at goal
Definition at line 250 of file cart_local_planner.h.
boost::shared_ptr<cart_local_planner::SBPLSubscriber<cart_pushing_msgs::RobotCartPath> > cart_local_planner::CartLocalPlanner::sbpl_subscriber_ [protected] |
Definition at line 277 of file cart_local_planner.h.
bool cart_local_planner::CartLocalPlanner::subscribe_sbpl_plan_ [protected] |
Definition at line 253 of file cart_local_planner.h.
Definition at line 212 of file cart_local_planner.h.
Definition at line 211 of file cart_local_planner.h.
double cart_local_planner::CartLocalPlanner::tolerance_rot_ [protected] |
Definition at line 249 of file cart_local_planner.h.
double cart_local_planner::CartLocalPlanner::tolerance_timeout_ [protected] |
Goal threshold tolerances
Definition at line 249 of file cart_local_planner.h.
double cart_local_planner::CartLocalPlanner::tolerance_trans_ [protected] |
Definition at line 249 of file cart_local_planner.h.
double cart_local_planner::CartLocalPlanner::trans_stopped_velocity_ [protected] |
Definition at line 250 of file cart_local_planner.h.
Pointer to cmd_vel, the Twist for returning to move_base
Definition at line 240 of file cart_local_planner.h.
Definition at line 268 of file cart_local_planner.h.
TwistStamped for writing to cart command_vel topic
Definition at line 241 of file cart_local_planner.h.
Definition at line 268 of file cart_local_planner.h.
Definition at line 220 of file cart_local_planner.h.
Definition at line 258 of file cart_local_planner.h.