Skip to content

Steering rate #155

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 7 commits into
base: kinetic-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 9 additions & 0 deletions cfg/TebLocalPlannerReconfigure.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -97,6 +97,11 @@ gen.add("min_turning_radius", double_t, 0,
"Minimum turning radius of a carlike robot (diff-drive robot: zero)",
0.0, 0.0, 50.0)

gen.add("max_steering_rate", double_t, 0,
"EXPERIMENTAL: Maximum steering rate of a carlike robot (THIS SIGNIFICANTLY AFFECTS PERFORMANCE AT THE MOMENT) [deactivate: zero]",
0.0, 0.0, 10.0)


gen.add("wheelbase", double_t, 0,
"The distance between the drive shaft and steering axle (only required for a carlike robot with 'cmd_angle_instead_rotvel' enabled); The value might be negative for back-wheeled robots!",
1.0, -10.0, 10.0)
Expand Down Expand Up @@ -222,6 +227,10 @@ gen.add("weight_kinematics_forward_drive", double_t, 0,
gen.add("weight_kinematics_turning_radius", double_t, 0,
"Optimization weight for enforcing a minimum turning radius (carlike robots)",
1, 0, 1000)

gen.add("weight_max_steering_rate", double_t, 0,
"EXPERIMENTAL: Optimization weight for enforcing a minimum steering rate of a carlike robot (TRY TO KEEP THE WEIGHT LOW OR DEACTIVATE, SINCE IT SIGNIFICANTLY AFFECTS PERFORMANCE AT THE MOMENT)",
0.5, 0, 100)

gen.add("weight_optimaltime", double_t, 0,
"Optimization weight for contracting the trajectory w.r.t transition time",
Expand Down
6 changes: 3 additions & 3 deletions include/teb_local_planner/g2o_types/edge_acceleration.h
Original file line number Diff line number Diff line change
Expand Up @@ -121,16 +121,16 @@ class EdgeAcceleration : public BaseTebMultiEdge<2, double>
dist2 = fabs( angle_diff2 * radius ); // actual arg length!
}
}

double vel1 = dist1 / dt1->dt();
double vel2 = dist2 / dt2->dt();


// consider directions
// vel1 *= g2o::sign(diff1[0]*cos(pose1->theta()) + diff1[1]*sin(pose1->theta()));
// vel2 *= g2o::sign(diff2[0]*cos(pose2->theta()) + diff2[1]*sin(pose2->theta()));
vel1 *= fast_sigmoid( 100*(diff1.x()*cos(pose1->theta()) + diff1.y()*sin(pose1->theta())) );
vel2 *= fast_sigmoid( 100*(diff2.x()*cos(pose2->theta()) + diff2.y()*sin(pose2->theta())) );
vel1 *= fast_sigmoid( 100*(diff1.x()*cos(pose1->theta()) + diff1.y()*sin(pose1->theta())) );
vel2 *= fast_sigmoid( 100*(diff2.x()*cos(pose2->theta()) + diff2.y()*sin(pose2->theta())) );

const double acc_lin = (vel2 - vel1)*2 / ( dt1->dt() + dt2->dt() );

Expand Down
231 changes: 226 additions & 5 deletions include/teb_local_planner/g2o_types/edge_velocity.h
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ class EdgeVelocity : public BaseTebMultiEdge<2, double>
double vel = dist / deltaT->estimate();

// vel *= g2o::sign(deltaS[0]*cos(conf1->theta()) + deltaS[1]*sin(conf1->theta())); // consider direction
vel *= fast_sigmoid( 100 * (deltaS.x()*cos(conf1->theta()) + deltaS.y()*sin(conf1->theta())) ); // consider direction
vel *= fast_sigmoid( 100.0 * (deltaS.x()*cos(conf1->theta()) + deltaS.y()*sin(conf1->theta())) ); // consider direction

const double omega = angle_diff / deltaT->estimate();

Expand Down Expand Up @@ -198,10 +198,6 @@ class EdgeVelocity : public BaseTebMultiEdge<2, double>
};






/**
* @class EdgeVelocityHolonomic
* @brief Edge defining the cost function for limiting the translational and rotational velocity according to x,y and theta.
Expand Down Expand Up @@ -268,6 +264,231 @@ class EdgeVelocityHolonomic : public BaseTebMultiEdge<3, double>
};



/**
* @class EdgeSteeringRate
* @brief Edge defining the cost function for limiting the steering rate w.r.t. the current wheelbase parameter
*
* The edge depends on four vertices \f$ \mathbf{s}_i, \mathbf{s}_{ip1}, \mathbf{s}_{ip2} \Delta T_i \f$ .
* @remarks This edge requires the TebConfig::Robot::whelbase parameter to be set.
* @remarks Do not forget to call setTebConfig()
*/
class EdgeSteeringRate : public BaseTebMultiEdge<1, double>
{
public:

/**
* @brief Construct edge.
*/
EdgeSteeringRate()
{
this->resize(5); // Since we derive from a g2o::BaseMultiEdge, set the desired number of vertices
}

/**
* @brief Actual cost function
*/
void computeError()
{
ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeSteeringRate()");
const VertexPose* conf1 = static_cast<const VertexPose*>(_vertices[0]);
const VertexPose* conf2 = static_cast<const VertexPose*>(_vertices[1]);
const VertexPose* conf3 = static_cast<const VertexPose*>(_vertices[2]);
const VertexTimeDiff* dt1 = static_cast<const VertexTimeDiff*>(_vertices[3]);
const VertexTimeDiff* dt2 = static_cast<const VertexTimeDiff*>(_vertices[4]);

Eigen::Vector2d delta_s1 = conf2->estimate().position() - conf1->estimate().position();
Eigen::Vector2d delta_s2 = conf3->estimate().position() - conf2->estimate().position();
double dist1 = delta_s1.norm();
double dist2 = delta_s2.norm();
double angle_diff1 = g2o::normalize_theta( conf2->theta() - conf1->theta() );
double angle_diff2 = g2o::normalize_theta( conf3->theta() - conf2->theta() );

double phi1, phi2;
if (std::abs(dist1) < 1e-12)
{
phi1 = 0; // TODO previous phi?
//ROS_INFO("phi 1 is zero!");
}
else
{
//dist1 *= fast_sigmoid( 100.0 * (delta_s1.x()*cos(conf1->theta()) + delta_s1.y()*sin(conf1->theta())) ); // consider direction
//if (delta_s1.x()*cos(conf1->theta()) + delta_s1.y()*sin(conf1->theta()) < 0)
//dist1 = -dist1;

if (cfg_->trajectory.exact_arc_length)
phi1 = std::atan(cfg_->robot.wheelbase / dist1 * 2.0*std::sin(angle_diff1/2.0));
else
phi1 = std::atan(cfg_->robot.wheelbase / dist1 * angle_diff1);

// if we compute the sign of dist1 using the following method, the optimizer get's stuck (possibly due to non-smoothness and atan)
// In case if we apply the sign to the angle directly, it seems to work:
phi1 *= fast_sigmoid( 100.0 * (delta_s1.x()*cos(conf1->theta()) + delta_s1.y()*sin(conf1->theta())) ); // consider direction
}

if (std::abs(dist2) < 1e-12)
{
phi2 = phi1;
ROS_INFO("phi 2 is phi1!");
}
else
{
//dist2 *= fast_sigmoid( 100.0 * (delta_s2.x()*cos(conf2->theta()) + delta_s2.y()*sin(conf2->theta())) ); // consider direction
//if (delta_s2.x()*cos(conf2->theta()) + delta_s2.y()*sin(conf2->theta()) < 0)
// dist2 = -dist2;

if (cfg_->trajectory.exact_arc_length)
phi2 = std::atan(cfg_->robot.wheelbase / dist2 * 2.0*std::sin(angle_diff2/2.0));
else
phi2 = std::atan(cfg_->robot.wheelbase / dist2 * angle_diff2);

// if we compute the sign of dist1 using the following method, the optimizer get's stuck (possibly due to non-smoothness and atan).
// In case if we apply the sign to the angle directly, it seems to work:
phi2 *= fast_sigmoid( 100.0 * (delta_s2.x()*cos(conf2->theta()) + delta_s2.y()*sin(conf2->theta())) ); // consider direction
}

_error[0] = penaltyBoundToInterval(g2o::normalize_theta(phi2 - phi1)*2.0 / (dt1->dt() + dt2->dt()), cfg_->robot.max_steering_rate, 0.0);

ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeSteeringRate::computeError() _error[0]\n",_error[0]);
}

public:

EIGEN_MAKE_ALIGNED_OPERATOR_NEW

};

//! Corresponds to EdgeSteeringRate but with initial steering angle for the predecessor configuration
class EdgeSteeringRateStart : public BaseTebMultiEdge<1, double>
{
public:

/**
* @brief Construct edge.
*/
EdgeSteeringRateStart()
{
this->resize(3); // Since we derive from a g2o::BaseMultiEdge, set the desired number of vertices
}

/**
* @brief Actual cost function
*/
void computeError()
{
ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeSteeringRateStart()");
const VertexPose* conf1 = static_cast<const VertexPose*>(_vertices[0]);
const VertexPose* conf2 = static_cast<const VertexPose*>(_vertices[1]);
const VertexTimeDiff* dt = static_cast<const VertexTimeDiff*>(_vertices[2]);

Eigen::Vector2d delta_s = conf2->estimate().position() - conf1->estimate().position();
double dist = delta_s.norm();
double angle_diff = g2o::normalize_theta( conf2->theta() - conf1->theta() );

double phi;
if (std::abs(dist) < 1e-12)
{
ROS_INFO("Start phi equals pervious phi!");
phi = _measurement;
}
else
{
//dist *= fast_sigmoid( 100.0 * (delta_s.x()*cos(conf1->theta()) + delta_s.y()*sin(conf1->theta())) ); // consider direction
//dist *= (double)g2o::sign( delta_s.x()*cos(conf1->theta()) + delta_s.y()*sin(conf1->theta()) ); // consider direction

if (cfg_->trajectory.exact_arc_length)
phi = std::atan(cfg_->robot.wheelbase / dist * 2.0*std::sin(angle_diff/2.0));
else
phi = std::atan(cfg_->robot.wheelbase / dist * angle_diff);

// if we compute the sign of dist1 using the following method, the optimizer get's stuck (possibly due to non-smoothness and atan).
// In case if we apply the sign to the angle directly, it seems to work:
phi *= fast_sigmoid( 100.0 * (delta_s.x()*cos(conf1->theta()) + delta_s.y()*sin(conf1->theta())) ); // consider direction
}

_error[0] = penaltyBoundToInterval(g2o::normalize_theta(phi - _measurement) / dt->dt(), cfg_->robot.max_steering_rate, 0.0);


ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeSteeringRateStart::computeError() _error[0]\n",_error[0]);
}

void setInitialSteeringAngle(double steering_angle)
{
_measurement = steering_angle;
}

public:

EIGEN_MAKE_ALIGNED_OPERATOR_NEW

};

//! Corresponds to EdgeSteeringRate but with initial steering angle for the successor configuration
class EdgeSteeringRateGoal : public BaseTebMultiEdge<1, double>
{
public:

/**
* @brief Construct edge.
*/
EdgeSteeringRateGoal()
{
this->resize(3); // Since we derive from a g2o::BaseMultiEdge, set the desired number of vertices
}

/**
* @brief Actual cost function
*/
void computeError()
{
ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeSteeringRateGoal()");
const VertexPose* conf1 = static_cast<const VertexPose*>(_vertices[0]);
const VertexPose* conf2 = static_cast<const VertexPose*>(_vertices[1]);
const VertexTimeDiff* dt = static_cast<const VertexTimeDiff*>(_vertices[2]);

Eigen::Vector2d delta_s = conf2->estimate().position() - conf1->estimate().position();
double dist = delta_s.norm();
double angle_diff = g2o::normalize_theta( conf2->theta() - conf1->theta() );

double phi;
if (std::abs(dist) < 1e-12)
{
ROS_INFO("Goal phi is zero!");
phi = 0;
}
else
{
//dist *= fast_sigmoid( 100.0 * (delta_s.x()*cos(conf1->theta()) + delta_s.y()*sin(conf1->theta())) ); // consider direction

if (cfg_->trajectory.exact_arc_length)
phi = std::atan(cfg_->robot.wheelbase / dist * 2.0*std::sin(angle_diff/2.0));
else
phi = std::atan(cfg_->robot.wheelbase / dist * angle_diff);

// if we compute the sign of dist1 using the following method, the optimizer get's stuck (possibly due to non-smoothness and atan).
// In case if we apply the sign to the angle directly, it seems to work:
phi *= fast_sigmoid( 100.0 * (delta_s.x()*cos(conf1->theta()) + delta_s.y()*sin(conf1->theta())) ); // consider direction
}

_error[0] = penaltyBoundToInterval(g2o::normalize_theta(_measurement - phi) / dt->dt(), cfg_->robot.max_steering_rate, 0.0);


ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeSteeringRateGoal::computeError() _error[0]\n",_error[0]);
}

void setGoalSteeringAngle(double steering_angle)
{
_measurement = steering_angle;
}

public:

EIGEN_MAKE_ALIGNED_OPERATOR_NEW

};



} // end namespace

#endif
2 changes: 1 addition & 1 deletion include/teb_local_planner/misc.h
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ inline bool smaller_than_abs(double i, double j) {return std::fabs(i)<std::fabs(
*/
inline double fast_sigmoid(double x)
{
return x / (1 + fabs(x));
return x / (1.0 + fabs(x));
}

/**
Expand Down
9 changes: 9 additions & 0 deletions include/teb_local_planner/optimal_planner.h
Original file line number Diff line number Diff line change
Expand Up @@ -664,6 +664,14 @@ class TebOptimalPlanner : public PlannerInterface
*/
void AddEdgesKinematicsCarlike();

/**
* @brief Add all edges (local cost functions) for satisfying a maximum steering rate of a carlike robot
* @warning requires a valid wheelbase parameter value!
* @see buildGraph
* @see optimizeGraph
*/
void AddEdgesSteeringRate();

/**
* @brief Add all edges (local cost functions) for prefering a specifiy turning direction (by penalizing the other one)
* @see buildGraph
Expand Down Expand Up @@ -696,6 +704,7 @@ class TebOptimalPlanner : public PlannerInterface
boost::shared_ptr<g2o::SparseOptimizer> optimizer_; //!< g2o optimizer for trajectory optimization
std::pair<bool, geometry_msgs::Twist> vel_start_; //!< Store the initial velocity at the start pose
std::pair<bool, geometry_msgs::Twist> vel_goal_; //!< Store the final velocity at the goal pose
double recent_steering_angle_ = 0.0; //!< Store last measured steering angle (for car-like setup)

bool initialized_; //!< Keeps track about the correct initialization of this class
bool optimized_; //!< This variable is \c true as long as the last optimization has been completed successful
Expand Down
4 changes: 4 additions & 0 deletions include/teb_local_planner/teb_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,7 @@ class TebConfig
double acc_lim_y; //!< Maximum strafing acceleration of the robot
double acc_lim_theta; //!< Maximum angular acceleration of the robot
double min_turning_radius; //!< Minimum turning radius of a carlike robot (diff-drive robot: zero);
double max_steering_rate; //!< EXPERIMENTAL: Maximum steering rate of a carlike robot (THIS SIGNIFICANTLY AFFECTS PERFORMANCE AT THE MOMENT) [deactivate: zero]
double wheelbase; //!< The distance between the drive shaft and steering axle (only required for a carlike robot with 'cmd_angle_instead_rotvel' enabled); The value might be negative for back-wheeled robots!
bool cmd_angle_instead_rotvel; //!< Substitute the rotational velocity in the commanded velocity message by the corresponding steering angle (check 'axles_distance')
bool is_footprint_dynamic; //<! If true, updated the footprint before checking trajectory feasibility
Expand Down Expand Up @@ -148,6 +149,7 @@ class TebConfig
double weight_kinematics_nh; //!< Optimization weight for satisfying the non-holonomic kinematics
double weight_kinematics_forward_drive; //!< Optimization weight for forcing the robot to choose only forward directions (positive transl. velocities, only diffdrive robot)
double weight_kinematics_turning_radius; //!< Optimization weight for enforcing a minimum turning radius (carlike robots)
double weight_max_steering_rate; //!< EXPERIMENTAL: Optimization weight for enforcing a minimum steering rate of a carlike robot (TRY TO KEEP THE WEIGHT LOW OR DEACTIVATE, SINCE IT SIGNIFICANTLY AFFECTS PERFORMANCE AT THE MOMENT)
double weight_optimaltime; //!< Optimization weight for contracting the trajectory w.r.t transition time
double weight_obstacle; //!< Optimization weight for satisfying a minimum separation from obstacles
double weight_inflation; //!< Optimization weight for the inflation penalty (should be small)
Expand Down Expand Up @@ -246,6 +248,7 @@ class TebConfig
robot.acc_lim_y = 0.5;
robot.acc_lim_theta = 0.5;
robot.min_turning_radius = 0;
robot.max_steering_rate = 0;
robot.wheelbase = 1.0;
robot.cmd_angle_instead_rotvel = false;
robot.is_footprint_dynamic = false;
Expand Down Expand Up @@ -289,6 +292,7 @@ class TebConfig
optim.weight_kinematics_nh = 1000;
optim.weight_kinematics_forward_drive = 1;
optim.weight_kinematics_turning_radius = 1;
optim.weight_max_steering_rate = 1;
optim.weight_optimaltime = 1;
optim.weight_obstacle = 50;
optim.weight_inflation = 0.1;
Expand Down
Loading