87 geometry_msgs::Pose2D tmp_pose2D;
90 tmp_pose2D.theta = 0.0;
98 ROS_WARN(
"This planner has already been initialized, doing nothing.");
104 eband_local_planner::EBandPlannerConfig& config)
114 k_p_ = config.k_prop;
115 k_nu_ = config.k_damp;
148 odom_vel_.linear.x = odometry.twist.twist.linear.x;
149 odom_vel_.linear.y = odometry.twist.twist.linear.y;
153 odom_vel_.angular.z = odometry.twist.twist.angular.z;
161 const geometry_msgs::Pose& pose)
163 const double pi = 3.14159265;
164 const double t1 =
atan2(heading.linear.y, heading.linear.x);
166 const double d = t1-t2;
177 goal_reached =
false;
179 geometry_msgs::Twist robot_cmd, bubble_diff;
180 robot_cmd.linear.x = 0.0;
181 robot_cmd.angular.z = 0.0;
183 bool command_provided =
false;
187 ROS_ERROR(
"Requesting feedforward command from not initialized planner. Please call initialize() before using this planner");
193 ROS_WARN(
"Requesting feedforward command from empty band.");
203 float distance_from_goal = -1.0f;
207 if (!command_provided) {
208 int curr_target_bubble = 1;
210 while(curr_target_bubble < ((
int)
elastic_band_.size()) - 1) {
211 curr_target_bubble++;
234 distance_from_goal = sqrtf(bubble_diff.linear.x * bubble_diff.linear.x +
235 bubble_diff.linear.y * bubble_diff.linear.y);
249 ROS_DEBUG(
"Performing in place rotation for goal (diff): %f", orientation_diff);
250 double rotation_sign = -2 * (orientation_diff < 0) + 1;
251 robot_cmd.angular.z =
258 ROS_INFO (
"TrajectoryController: Goal reached with distance %.2f, %.2f (od = %.2f)" 259 "; sending zero velocity",
260 bubble_diff.linear.x, bubble_diff.linear.y, orientation_diff);
262 robot_cmd.linear.x = 0.0;
263 robot_cmd.angular.z = 0.0;
266 command_provided =
true;
277 if (!command_provided) {
278 ROS_DEBUG(
"Goal has not been reached, performing checks to move towards goal");
281 double distance_to_next_bubble =
sqrt(
282 bubble_diff.linear.x * bubble_diff.linear.x +
283 bubble_diff.linear.y * bubble_diff.linear.y);
284 double radius_of_next_bubble = 0.7 *
elastic_band_.at(1).expansion;
285 double in_place_rotation_threshold =
287 fabs(
atan2(radius_of_next_bubble,distance_to_next_bubble));
288 ROS_DEBUG(
"In-place rotation threshold: %f(%f,%f)",
289 in_place_rotation_threshold, radius_of_next_bubble, distance_to_next_bubble);
292 if (fabs(bubble_diff.angular.z) > in_place_rotation_threshold) {
293 robot_cmd.angular.z =
k_p_ * bubble_diff.angular.z;
294 double rotation_sign = (bubble_diff.angular.z < 0) ? -1.0 : +1.0;
301 ROS_DEBUG(
"Performing in place rotation for start (diff): %f with rot vel: %f", bubble_diff.angular.z, robot_cmd.angular.z);
302 command_provided =
true;
308 if (!command_provided) {
311 double forward_sign = -2 * (bubble_diff.linear.x < 0) + 1;
316 if (distance_from_goal < 0.75
f) {
317 max_vel_lin = (max_vel_lin < 0.3) ? 0.15 : max_vel_lin / 2;
320 double linear_velocity = velocity_multiplier * max_vel_lin;
321 linear_velocity *=
cos(bubble_diff.angular.z);
329 double error = bubble_diff.angular.z;
330 double rotation_sign = -2 * (bubble_diff.angular.z < 0) + 1;
331 double angular_velocity =
k_p_ * error;
338 ROS_DEBUG(
"Selected velocity: lin: %f, ang: %f",
339 linear_velocity, angular_velocity);
341 robot_cmd.linear.x = linear_velocity;
342 robot_cmd.angular.z = angular_velocity;
343 command_provided =
true;
346 twist_cmd = robot_cmd;
347 ROS_DEBUG(
"Final command: %f, %f", twist_cmd.linear.x, twist_cmd.angular.z);
354 goal_reached =
false;
360 geometry_msgs::Twist robot_cmd, bubble_diff, control_deviation;
361 robot_cmd.linear.x = 0.0;
362 robot_cmd.linear.y = 0.0;
363 robot_cmd.linear.z = 0.0;
364 robot_cmd.angular.x = 0.0;
365 robot_cmd.angular.y = 0.0;
366 robot_cmd.angular.z = 0.0;
369 twist_cmd = robot_cmd;
370 control_deviation = robot_cmd;
375 ROS_ERROR(
"Requesting feedforward command from not initialized planner. Please call initialize() before using this planner");
382 ROS_WARN(
"Requesting feedforward command from empty band.");
392 double bubble_distance, ang_pseudo_dist;
397 bubble_distance =
sqrt( (bubble_diff.linear.x * bubble_diff.linear.x) + (bubble_diff.linear.y * bubble_diff.linear.y) +
398 (ang_pseudo_dist * ang_pseudo_dist) );
408 control_deviation = bubble_diff;
412 abs_ctrl_dev =
sqrt( (control_deviation.linear.x * control_deviation.linear.x) +
413 (control_deviation.linear.y * control_deviation.linear.y) +
414 (ang_pseudo_dist * ang_pseudo_dist) );
417 if(scaled_radius < bubble_distance)
420 double scale_difference = scaled_radius / bubble_distance;
421 bubble_diff.linear.x *= scale_difference;
422 bubble_diff.linear.y *= scale_difference;
423 bubble_diff.angular.z *= scale_difference;
425 control_deviation = bubble_diff;
430 if(scaled_radius > bubble_distance)
436 double next_bubble_distance;
437 geometry_msgs::Twist next_bubble_diff;
442 next_bubble_distance =
sqrt( (next_bubble_diff.linear.x * next_bubble_diff.linear.x) +
443 (next_bubble_diff.linear.y * next_bubble_diff.linear.y) +
444 (ang_pseudo_dist * ang_pseudo_dist) );
446 if(scaled_radius > (bubble_distance + next_bubble_distance) )
449 control_deviation.linear.x = bubble_diff.linear.x + next_bubble_diff.linear.x;
450 control_deviation.linear.y = bubble_diff.linear.y + next_bubble_diff.linear.y;
451 control_deviation.angular.z = bubble_diff.angular.z + next_bubble_diff.angular.z;
463 double b_distance, cosine_at_bub;
464 double vec_prod, norm_vec1, norm_vec2;
465 double ang_pseudo_dist1, ang_pseudo_dist2;
471 vec_prod = - ( (bubble_diff.linear.x * next_bubble_diff.linear.x) +
472 (bubble_diff.linear.y * next_bubble_diff.linear.y) +
473 (ang_pseudo_dist1 * ang_pseudo_dist2) );
475 norm_vec1 =
sqrt( (bubble_diff.linear.x * bubble_diff.linear.x) +
476 (bubble_diff.linear.y * bubble_diff.linear.y) +
477 (ang_pseudo_dist1 * ang_pseudo_dist1) );
479 norm_vec2 =
sqrt( (next_bubble_diff.linear.x * next_bubble_diff.linear.x) +
480 (next_bubble_diff.linear.y * next_bubble_diff.linear.y) +
481 (ang_pseudo_dist2 * ang_pseudo_dist2) );
484 cosine_at_bub = vec_prod / norm_vec1 / norm_vec2;
485 b_distance = bubble_distance * cosine_at_bub +
sqrt( scaled_radius*scaled_radius -
486 bubble_distance*bubble_distance * (1.0 - cosine_at_bub*cosine_at_bub) );
489 double scale_next_difference = b_distance / next_bubble_distance;
490 next_bubble_diff.linear.x *= scale_next_difference;
491 next_bubble_diff.linear.y *= scale_next_difference;
492 next_bubble_diff.angular.z *= scale_next_difference;
495 control_deviation.linear.x = bubble_diff.linear.x + next_bubble_diff.linear.x;
496 control_deviation.linear.y = bubble_diff.linear.y + next_bubble_diff.linear.y;
497 control_deviation.angular.z = bubble_diff.angular.z + next_bubble_diff.angular.z;
505 abs_ctrl_dev =
sqrt( (control_deviation.linear.x * control_deviation.linear.x) +
506 (control_deviation.linear.y * control_deviation.linear.y) +
507 (ang_pseudo_dist * ang_pseudo_dist) );
513 geometry_msgs::Pose2D tmp_bubble_2d, curr_bubble_2d;
514 geometry_msgs::Pose tmp_pose;
518 tmp_bubble_2d.x = curr_bubble_2d.x + control_deviation.linear.x;
519 tmp_bubble_2d.y = curr_bubble_2d.y + control_deviation.linear.y;
520 tmp_bubble_2d.theta = curr_bubble_2d.theta + control_deviation.angular.z;
522 new_bubble.
center.pose = tmp_pose;
528 const geometry_msgs::Point& goal = (--
elastic_band_.end())->center.pose.position;
529 const double dx =
elastic_band_.at(0).center.pose.position.x - goal.x;
530 const double dy =
elastic_band_.at(0).center.pose.position.y - goal.y;
531 const double dist_to_goal =
sqrt(dx*dx + dy*dy);
541 control_deviation.angular.z = vel*mult;
542 const double abs_vel = fabs(control_deviation.angular.z);
545 "Angular diff is %.2f and desired angular " 546 "vel is %.2f. Initial translation velocity " 547 "is %.2f, %.2f", angular_diff,
548 control_deviation.angular.z,
549 control_deviation.linear.x,
550 control_deviation.linear.y);
552 control_deviation.linear.x *= trans_mult;
553 control_deviation.linear.y *= trans_mult;
555 "Translation multiplier is %.2f and scaled " 556 "translational velocity is %.2f, %.2f",
557 trans_mult, control_deviation.linear.x,
558 control_deviation.linear.y);
562 "Not applying angle correction because " 563 "distance to goal is %.2f", dist_to_goal);
569 geometry_msgs::Twist desired_velocity, currbub_maxvel_dir;
570 double desvel_abs, desvel_abs_trans, currbub_maxvel_abs;
571 double scale_des_vel;
572 desired_velocity = robot_cmd;
573 currbub_maxvel_dir = robot_cmd;
576 desired_velocity.linear.x =
k_p_/
k_nu_ * control_deviation.linear.x;
577 desired_velocity.linear.y =
k_p_/
k_nu_ * control_deviation.linear.y;
578 desired_velocity.angular.z =
k_p_/
k_nu_ * control_deviation.angular.z;
583 int curr_bub_num = 0;
588 desvel_abs =
sqrt( (desired_velocity.linear.x * desired_velocity.linear.x) +
589 (desired_velocity.linear.y * desired_velocity.linear.y) +
590 (ang_pseudo_dist * ang_pseudo_dist) );
591 if(desvel_abs > currbub_maxvel_abs)
593 scale_des_vel = currbub_maxvel_abs / desvel_abs;
594 desired_velocity.linear.x *= scale_des_vel;
595 desired_velocity.linear.y *= scale_des_vel;
596 desired_velocity.angular.z *= scale_des_vel;
600 desvel_abs_trans =
sqrt( (desired_velocity.linear.x * desired_velocity.linear.x) + (desired_velocity.linear.y * desired_velocity.linear.y) );
605 desired_velocity.linear.x *= scale_des_vel;
606 desired_velocity.linear.y *= scale_des_vel;
608 desired_velocity.angular.z *= scale_des_vel;
614 scale_des_vel =
max_vel_th_ / fabs(desired_velocity.angular.z);
615 desired_velocity.angular.z *= scale_des_vel;
617 desired_velocity.linear.x *= scale_des_vel;
618 desired_velocity.linear.y *= scale_des_vel;
622 geometry_msgs::Twist acc_desired;
623 acc_desired = robot_cmd;
630 double abs_acc_trans =
sqrt( (acc_desired.linear.x*acc_desired.linear.x) + (acc_desired.linear.y*acc_desired.linear.y) );
634 acc_desired.linear.x *= scale_acc;
635 acc_desired.linear.y *= scale_acc;
637 acc_desired.angular.z *= scale_acc;
643 acc_desired.angular.z *= scale_acc;
645 acc_desired.linear.x *= scale_acc;
646 acc_desired.linear.y *= scale_acc;
667 int curr_target_bubble = 1;
674 curr_target_bubble++;
683 "Goal reached with distance %.2f, %.2f, %.2f" 684 "; sending zero velocity",
685 bubble_diff.linear.x, bubble_diff.linear.y,
686 bubble_diff.angular.z);
688 robot_cmd.linear.x = 0.0;
689 robot_cmd.linear.y = 0.0;
690 robot_cmd.angular.z = 0.0;
700 twist_cmd = robot_cmd;
709 VelDir.linear.x = 0.0;
710 VelDir.linear.y = 0.0;
711 VelDir.linear.z = 0.0;
712 VelDir.angular.x = 0.0;
713 VelDir.angular.y = 0.0;
714 VelDir.angular.z = 0.0;
717 if(target_bub_num >= ((
int) band.size() - 1))
722 double v_max_curr_bub, v_max_next_bub;
723 double bubble_distance, angle_to_pseudo_vel, delta_vel_max;
724 geometry_msgs::Twist bubble_diff;
730 ROS_ASSERT( (target_bub_num >= 0) && ((target_bub_num +1) < (
int) band.size()) );
735 bubble_distance =
sqrt( (bubble_diff.linear.x * bubble_diff.linear.x) + (bubble_diff.linear.y * bubble_diff.linear.y) +
736 (angle_to_pseudo_vel * angle_to_pseudo_vel) );
739 VelDir.linear.x =bubble_diff.linear.x/bubble_distance;
740 VelDir.linear.y =bubble_diff.linear.y/bubble_distance;
741 VelDir.angular.z =bubble_diff.angular.z/bubble_distance;
744 if(bubble_distance > band.at(target_bub_num).expansion )
745 return v_max_curr_bub;
749 int next_bub_num = target_bub_num + 1;
750 geometry_msgs::Twist dummy_twist;
754 if(v_max_next_bub >= v_max_curr_bub)
755 return v_max_curr_bub;
760 v_max_curr_bub = v_max_next_bub + delta_vel_max;
762 return v_max_curr_bub;
769 geometry_msgs::Pose2D frame1_pose2D, frame2_pose2D, ref_frame_pose2D;
770 geometry_msgs::Pose2D frame1_pose2D_rf, frame2_pose2D_rf;
771 geometry_msgs::Twist frame_diff;
779 frame1_pose2D_rf.x = (frame1_pose2D.x - ref_frame_pose2D.x) *
cos(ref_frame_pose2D.theta) +
780 (frame1_pose2D.y - ref_frame_pose2D.y) *
sin(ref_frame_pose2D.theta);
781 frame1_pose2D_rf.y = -(frame1_pose2D.x - ref_frame_pose2D.x) *
sin(ref_frame_pose2D.theta) +
782 (frame1_pose2D.y - ref_frame_pose2D.y) *
cos(ref_frame_pose2D.theta);
783 frame1_pose2D_rf.theta = frame1_pose2D.theta - ref_frame_pose2D.theta;
786 frame2_pose2D_rf.x = (frame2_pose2D.x - ref_frame_pose2D.x) *
cos(ref_frame_pose2D.theta) +
787 (frame2_pose2D.y - ref_frame_pose2D.y) *
sin(ref_frame_pose2D.theta);
788 frame2_pose2D_rf.y = -(frame2_pose2D.x - ref_frame_pose2D.x) *
sin(ref_frame_pose2D.theta) +
789 (frame2_pose2D.y - ref_frame_pose2D.y) *
cos(ref_frame_pose2D.theta);
790 frame2_pose2D_rf.theta = frame2_pose2D.theta - ref_frame_pose2D.theta;
794 frame_diff.linear.x = frame2_pose2D_rf.x - frame1_pose2D_rf.x;
795 frame_diff.linear.y = frame2_pose2D_rf.y - frame1_pose2D_rf.y;
796 frame_diff.linear.z = 0.0;
797 frame_diff.angular.x = 0.0;
798 frame_diff.angular.y = 0.0;
799 frame_diff.angular.z = frame2_pose2D_rf.theta - frame1_pose2D_rf.theta;
809 double x1 = frame1.position.x - ref_frame.position.x;
810 double y1 = frame1.position.y - ref_frame.position.y;
811 double x2 = frame2.position.x - ref_frame.position.x;
812 double y2 = frame2.position.y - ref_frame.position.y;
813 double yaw_ref =
tf2::getYaw(ref_frame.orientation);
815 double x_diff = x2 - x1;
816 double y_diff = y2 - y1;
817 double theta_diff =
atan2(y_diff, x_diff);
821 double x_final = x_diff *
cos(rotation) + y_diff *
sin(rotation);
822 double y_final = - x_diff * sin(rotation) + y_diff *
cos(rotation);
824 geometry_msgs::Twist twist_msg;
825 twist_msg.linear.x = x_final;
826 twist_msg.linear.y = y_final;
834 const geometry_msgs::Pose& frame1,
const geometry_msgs::Pose& frame2)
836 geometry_msgs::Pose2D frame1_pose2D, frame2_pose2D;
837 geometry_msgs::Twist tmp_transformed;
840 tmp_transformed = curr_twist;
847 delta_ang = frame2_pose2D.theta - frame1_pose2D.theta;
851 tmp_transformed.linear.x = curr_twist.linear.x *
cos(delta_ang) + curr_twist.linear.y *
sin(delta_ang);
852 tmp_transformed.linear.y = -curr_twist.linear.x *
sin(delta_ang) + curr_twist.linear.y *
cos(delta_ang);
854 return tmp_transformed;
860 geometry_msgs::Twist res = twist;
863 double lin_overshoot =
sqrt(res.linear.x * res.linear.x + res.linear.y * res.linear.y) /
max_vel_lin_;
864 double lin_undershoot =
min_vel_lin_ /
sqrt(res.linear.x * res.linear.x + res.linear.y * res.linear.y);
865 if (lin_overshoot > 1.0)
867 res.linear.x /= lin_overshoot;
868 res.linear.y /= lin_overshoot;
870 res.angular.z /= lin_overshoot;
874 if(lin_undershoot > 1.0)
876 res.linear.x *= lin_undershoot;
877 res.linear.y *= lin_undershoot;
885 res.angular.z *= scale;
887 res.linear.x *= scale;
888 res.linear.y *= scale;
904 ROS_DEBUG(
"Angular command %f", res.angular.z);
std::vector< Bubble > elastic_band_
bool disallow_hysteresis_
double rotation_threshold_multiplier_
geometry_msgs::Twist getFrame1ToFrame2InRefFrameNew(const geometry_msgs::Pose &frame1, const geometry_msgs::Pose &frame2, const geometry_msgs::Pose &ref_frame)
geometry_msgs::Twist transformTwistFromFrame1ToFrame2(const geometry_msgs::Twist &curr_twist, const geometry_msgs::Pose &frame1, const geometry_msgs::Pose &frame2)
double bubble_velocity_multiplier_
bool getTwist(geometry_msgs::Twist &twist_cmd, bool &goal_reached)
calculates a twist feedforward command from the current band
geometry_msgs::Twist getFrame1ToFrame2InRefFrame(const geometry_msgs::Pose &frame1, const geometry_msgs::Pose &frame2, const geometry_msgs::Pose &ref_frame)
Transforms Pose of frame 1 and 2 into reference frame and gets difference of frame 1 and 2...
bool setBand(const std::vector< Bubble > &elastic_band)
This sets the elastic_band to the trajectory controller.
double sign(double n)
defines sign of a double
void reconfigure(EBandPlannerConfig &config)
Reconfigures the parameters of the planner.
void Pose2DToPose(geometry_msgs::Pose &pose, const geometry_msgs::Pose2D pose2D)
Converts a frame of type Pose to type Pose2D (mainly -> conversion of orientation from euler angles t...
EBandTrajectoryCtrl()
Default constructor.
bool setOdometry(const nav_msgs::Odometry &odometry)
This sets the robot velocity as provided by odometry.
double min_in_place_vel_th_
double angularDiff(const geometry_msgs::Twist &heading, const geometry_msgs::Pose &pose)
geometry_msgs::Twist last_vel_
bool differential_drive_hack_
~EBandTrajectoryCtrl()
Destructor.
geometry_msgs::Twist odom_vel_
bool getTwistDifferentialDrive(geometry_msgs::Twist &twist_cmd, bool &goal_reached)
double getCircumscribedRadius(costmap_2d::Costmap2DROS &costmap)
Gets the footprint of the robot and computes the circumscribed radius for the eband approach...
double in_place_trans_vel_
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
def normalize_angle(angle)
control_toolbox::Pid pid_
double rotation_correction_threshold_
geometry_msgs::Pose ref_frame_band_
double getYaw(const A &a)
void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)
Initializes the elastic band class by accesing costmap and loading parameters.
double getBubbleTargetVel(const int &target_bub_num, const std::vector< Bubble > &band, geometry_msgs::Twist &VelDir)
gets the max velocity allowed within this bubble depending on size of the bubble and pose and size of...
void setVisualization(boost::shared_ptr< EBandVisualization > target_visual)
passes a reference to the eband visualization object which can be used to visualize the band optimiza...
#define ROS_DEBUG_THROTTLE_NAMED(period, name,...)
boost::shared_ptr< EBandVisualization > target_visual_
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
geometry_msgs::Twist limitTwist(const geometry_msgs::Twist &twist)
limits the twist to the allowed range
geometry_msgs::PoseStamped center
costmap_2d::Costmap2DROS * costmap_ros_
pointer to costmap
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
double max(double a, double b)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
void PoseToPose2D(const geometry_msgs::Pose pose, geometry_msgs::Pose2D &pose2D)
Converts a frame of type Pose to type Pose2D (mainly -> conversion of orientation from quaternions to...