54 TwistRecovery::TwistRecovery () :
55 global_costmap_(NULL), local_costmap_(NULL),
tf_(NULL), initialized_(false)
82 ROS_FATAL_STREAM (
"Didn't find twist parameters in " << private_nh.getNamespace());
87 private_nh.param(
"duration",
duration_, 1.0);
101 gm::Twist
scaleTwist (
const gm::Twist& twist,
const double scale)
104 t.linear.x = twist.linear.x * scale;
105 t.linear.y = twist.linear.y * scale;
106 t.angular.z = twist.angular.z * scale;
110 gm::Pose2D
forwardSimulate (
const gm::Pose2D& p,
const gm::Twist& twist,
const double t=1.0)
113 p2.x = p.x + twist.linear.x*t;
114 p2.y = p.y + twist.linear.y*t;
115 p2.theta = p.theta + twist.angular.z*t;
123 return c < 0 ? 1e9 : c;
137 if (next_cost > cost) {
139 <<
" is " << next_cost <<
" which is greater than previous cost " << cost);
150 return sqrt(twist.linear.x*twist.linear.x + twist.linear.y*twist.linear.y);
155 return fabs(twist.angular.z);
165 const double acc_scaling = max(linear_acc_scaling, angular_acc_scaling);
168 const double vel_scaling = max(linear_vel_scaling, angular_vel_scaling);
169 return scaleTwist(twist, max(1.0, max(acc_scaling, vel_scaling)));
178 pose.x = p.getOrigin().x();
179 pose.y = p.getOrigin().y();
geometry_msgs::Twist scaleGivenAccelerationLimits(const geometry_msgs::Twist &twist, const double time_remaining) const
double linear_acceleration_limit_
void runBehavior()
Run the behavior.
#define ROS_INFO_NAMED(name,...)
double normalizedPoseCost(const geometry_msgs::Pose2D &pose) const
Return the cost of a pose, modified so that -1 does not equal infinity; instead 1e9 does...
#define ROS_DEBUG_STREAM_NAMED(name, args)
void publish(const boost::shared_ptr< M > &message) const
bool getRobotPose(tf::Stamped< tf::Pose > &global_pose) const
static double getYaw(const Quaternion &bt_q)
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
#define ROS_INFO_STREAM_NAMED(name, args)
gm::Pose2D forwardSimulate(const gm::Pose2D &p, const gm::Twist &twist, const double t=1.0)
base_local_planner::CostmapModel * world_model_
double controller_frequency_
geometry_msgs::Twist base_frame_twist_
costmap_2d::Costmap2DROS * global_costmap_
double angularSpeed(const gm::Twist &twist)
double linearSpeed(const gm::Twist &twist)
#define ROS_FATAL_STREAM(args)
double nonincreasingCostInterval(const geometry_msgs::Pose2D ¤t, const geometry_msgs::Twist &twist) const
double angular_acceleration_limit_
gm::Twist scaleTwist(const gm::Twist &twist, const double scale)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double linear_speed_limit_
tf::TransformListener * tf_
costmap_2d::Costmap2DROS * local_costmap_
virtual double footprintCost(const geometry_msgs::Point &position, const std::vector< geometry_msgs::Point > &footprint, double inscribed_radius, double circumscribed_radius)
double angular_speed_limit_
ROSCPP_DECL void shutdown()
geometry_msgs::Pose2D getCurrentLocalPose() const
void initialize(std::string n, tf::TransformListener *tf, costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap)
Initialize the parameters of the behavior.
std::vector< geometry_msgs::Point > getRobotFootprint()