44 : command_struct_twist_()
45 , command_struct_four_wheel_steering_()
47 , wheel_steering_y_offset_(0.0)
50 , cmd_vel_timeout_(0.5)
51 , base_frame_id_(
"base_link")
52 , enable_odom_tf_(true)
53 , enable_twist_cmd_(false)
61 const std::string complete_ns = controller_nh.
getNamespace();
62 std::size_t
id = complete_ns.find_last_of(
"/");
63 name_ = complete_ns.substr(
id + 1);
66 std::vector<std::string> front_wheel_names, rear_wheel_names;
67 if (!
getWheelNames(controller_nh,
"front_wheel", front_wheel_names) ||
68 !
getWheelNames(controller_nh,
"rear_wheel", rear_wheel_names))
73 if (front_wheel_names.size() != rear_wheel_names.size())
76 "#front wheels (" << front_wheel_names.size() <<
") != " <<
77 "#rear wheels (" << rear_wheel_names.size() <<
").");
80 else if (front_wheel_names.size() != 2)
83 "#two wheels by axle (left and right) is needed; now : "<<front_wheel_names.size()<<
" .");
93 std::vector<std::string> front_steering_names, rear_steering_names;
94 if (!
getWheelNames(controller_nh,
"front_steering", front_steering_names) ||
95 !
getWheelNames(controller_nh,
"rear_steering", rear_steering_names))
100 if (front_steering_names.size() != rear_steering_names.size())
103 "#left steerings (" << front_steering_names.size() <<
") != " <<
104 "#right steerings (" << rear_steering_names.size() <<
").");
107 else if (front_steering_names.size() != 2)
110 "#two steering by axle (left and right) is needed; now : "<<front_steering_names.size()<<
" .");
121 controller_nh.
param(
"publish_rate", publish_rate, 50.0);
123 << publish_rate <<
"Hz.");
128 int velocity_rolling_window_size = 10;
129 controller_nh.
param(
"velocity_rolling_window_size", velocity_rolling_window_size, velocity_rolling_window_size);
131 << velocity_rolling_window_size <<
".");
178 if(lookup_wheel_radius)
184 if(lookup_wheel_base)
194 "Odometry params : track " <<
track_ 209 "Adding front wheel with joint name: " << front_wheel_names[i]
210 <<
" and rear wheel with joint name: " << rear_wheel_names[i]);
219 "Adding left steering with joint name: " << front_steering_names[i]
220 <<
" and right steering with joint name: " << rear_steering_names[i]);
259 if (std::isnan(fl_speed) || std::isnan(fr_speed)
260 || std::isnan(rl_speed) || std::isnan(rr_speed))
267 if (std::isnan(fl_steering) || std::isnan(fr_steering)
268 || std::isnan(rl_steering) || std::isnan(rr_steering))
270 double front_steering_pos = 0.0;
271 if(fabs(fl_steering) > 0.001 || fabs(fr_steering) > 0.001)
273 front_steering_pos = atan(2*tan(fl_steering)*tan(fr_steering)/
274 (tan(fl_steering) + tan(fr_steering)));
276 double rear_steering_pos = 0.0;
277 if(fabs(rl_steering) > 0.001 || fabs(rr_steering) > 0.001)
279 rear_steering_pos = atan(2*tan(rl_steering)*tan(rr_steering)/
280 (tan(rl_steering) + tan(rr_steering)));
283 ROS_DEBUG_STREAM_THROTTLE(1,
"rl_steering "<<rl_steering<<
" rr_steering "<<rr_steering<<
" rear_steering_pos "<<rear_steering_pos);
286 front_steering_pos, rear_steering_pos, time);
293 const geometry_msgs::Quaternion orientation(
302 odom_pub_->msg_.pose.pose.orientation = orientation;
314 odom_4ws_pub_->msg_.data.front_steering_angle = front_steering_pos;
316 odom_4ws_pub_->msg_.data.rear_steering_angle = rear_steering_pos;
324 geometry_msgs::TransformStamped& odom_frame =
tf_odom_pub_->msg_.transforms[0];
325 odom_frame.header.stamp = time;
328 odom_frame.transform.rotation = orientation;
341 if(curr_cmd_4ws.
stamp >= curr_cmd_twist.
stamp)
348 cmd = &curr_cmd_twist;
352 const double dt = (time - cmd->
stamp).toSec();
356 curr_cmd_twist.
lin_x = 0.0;
357 curr_cmd_twist.
lin_y = 0.0;
358 curr_cmd_twist.
ang = 0.0;
359 curr_cmd_4ws.
lin = 0.0;
364 const double cmd_dt(period.
toSec());
370 double vel_left_front = 0, vel_right_front = 0;
371 double vel_left_rear = 0, vel_right_rear = 0;
372 double front_left_steering = 0, front_right_steering = 0;
373 double rear_left_steering = 0, rear_right_steering = 0;
384 if(fabs(curr_cmd_twist.
lin_x) > 0.001)
387 const double sign = copysign(1.0, curr_cmd_twist.
lin_x);
388 vel_left_front = sign * std::hypot((curr_cmd_twist.
lin_x - curr_cmd_twist.
ang*steering_track/2),
390 - vel_steering_offset;
391 vel_right_front = sign * std::hypot((curr_cmd_twist.
lin_x + curr_cmd_twist.
ang*steering_track/2),
393 + vel_steering_offset;
394 vel_left_rear = sign * std::hypot((curr_cmd_twist.
lin_x - curr_cmd_twist.
ang*steering_track/2),
396 - vel_steering_offset;
397 vel_right_rear = sign * std::hypot((curr_cmd_twist.
lin_x + curr_cmd_twist.
ang*steering_track/2),
399 + vel_steering_offset;
403 if(fabs(2.0*curr_cmd_twist.
lin_x) > fabs(curr_cmd_twist.
ang*steering_track))
406 (2.0*curr_cmd_twist.
lin_x - curr_cmd_twist.
ang*steering_track));
408 (2.0*curr_cmd_twist.
lin_x + curr_cmd_twist.
ang*steering_track));
410 else if(fabs(curr_cmd_twist.
lin_x) > 0.001)
412 front_left_steering = copysign(M_PI_2, curr_cmd_twist.
ang);
413 front_right_steering = copysign(M_PI_2, curr_cmd_twist.
ang);
415 rear_left_steering = -front_left_steering;
416 rear_right_steering = -front_right_steering;
428 const double tan_front_steering = tan(curr_cmd_4ws.
front_steering);
429 const double tan_rear_steering = tan(curr_cmd_4ws.
rear_steering);
431 const double steering_diff = steering_track*(tan_front_steering - tan_rear_steering)/2.0;
432 if(fabs(
wheel_base_ - fabs(steering_diff)) > 0.001)
441 if(fabs(curr_cmd_4ws.
lin) > 0.001)
446 if(fabs(tan(front_left_steering) - tan(front_right_steering)) > 0.01)
448 l_front = tan(front_right_steering) * tan(front_left_steering) * steering_track
449 / (tan(front_left_steering) - tan(front_right_steering));
453 if(fabs(tan(rear_left_steering) - tan(rear_right_steering)) > 0.01)
455 l_rear = tan(rear_right_steering) * tan(rear_left_steering) * steering_track
456 / (tan(rear_left_steering) - tan(rear_right_steering));
459 const double angular_speed_cmd = curr_cmd_4ws.
lin * (tan_front_steering-tan_rear_steering)/
wheel_base_;
461 const double sign = copysign(1.0, curr_cmd_4ws.
lin);
463 vel_left_front = sign * std::hypot((curr_cmd_4ws.
lin - angular_speed_cmd*steering_track/2),
465 - vel_steering_offset;
466 vel_right_front = sign * std::hypot((curr_cmd_4ws.
lin + angular_speed_cmd*steering_track/2),
468 + vel_steering_offset;
469 vel_left_rear = sign * std::hypot((curr_cmd_4ws.
lin - angular_speed_cmd*steering_track/2),
471 - vel_steering_offset;
472 vel_right_rear = sign * std::hypot((curr_cmd_4ws.
lin + angular_speed_cmd*steering_track/2),
474 + vel_steering_offset;
500 const double vel = 0.0;
507 const double pos = 0.0;
519 if(std::isnan(command.angular.z) || std::isnan(command.linear.x))
521 ROS_WARN(
"Received NaN in geometry_msgs::Twist. Ignoring command.");
530 "Added values to command. " 546 if(std::isnan(command.front_steering_angle) || std::isnan(command.rear_steering_angle)
547 || std::isnan(command.speed))
549 ROS_WARN(
"Received NaN in four_wheel_steering_msgs::FourWheelSteering. Ignoring command.");
558 "Added values to command. " 571 const std::string& wheel_param,
572 std::vector<std::string>& wheel_names)
575 if (!controller_nh.
getParam(wheel_param, wheel_list))
578 "Couldn't retrieve wheel param '" << wheel_param <<
"'.");
584 if (wheel_list.
size() == 0)
587 "Wheel param '" << wheel_param <<
"' is an empty list");
591 for (
int i = 0; i < wheel_list.
size(); ++i)
596 "Wheel param '" << wheel_param <<
"' #" << i <<
602 wheel_names.resize(wheel_list.
size());
603 for (
int i = 0; i < wheel_list.
size(); ++i)
605 wheel_names[i] =
static_cast<std::string
>(wheel_list[i]);
611 wheel_names.push_back(wheel_list);
616 "Wheel param '" << wheel_param <<
617 "' is neither a list of strings nor a string.");
627 controller_nh.
getParam(
"pose_covariance_diagonal", pose_cov_list);
630 for (
int i = 0; i < pose_cov_list.
size(); ++i)
634 controller_nh.
getParam(
"twist_covariance_diagonal", twist_cov_list);
637 for (
int i = 0; i < twist_cov_list.
size(); ++i)
642 odom_pub_->msg_.header.frame_id =
"odom";
644 odom_pub_->msg_.pose.pose.position.z = 0;
646 static_cast<double>(pose_cov_list[0]), 0., 0., 0., 0., 0.,
647 0., static_cast<double>(pose_cov_list[1]), 0., 0., 0., 0.,
648 0., 0.,
static_cast<double>(pose_cov_list[2]), 0., 0., 0.,
649 0., 0., 0., static_cast<double>(pose_cov_list[3]), 0., 0.,
650 0., 0., 0., 0.,
static_cast<double>(pose_cov_list[4]), 0.,
651 0., 0., 0., 0., 0., static_cast<double>(pose_cov_list[5]) };
652 odom_pub_->msg_.twist.twist.linear.y = 0;
653 odom_pub_->msg_.twist.twist.linear.z = 0;
654 odom_pub_->msg_.twist.twist.angular.x = 0;
655 odom_pub_->msg_.twist.twist.angular.y = 0;
657 static_cast<double>(twist_cov_list[0]), 0., 0., 0., 0., 0.,
658 0., static_cast<double>(twist_cov_list[1]), 0., 0., 0., 0.,
659 0., 0.,
static_cast<double>(twist_cov_list[2]), 0., 0., 0.,
660 0., 0., 0., static_cast<double>(twist_cov_list[3]), 0., 0.,
661 0., 0., 0., 0.,
static_cast<double>(twist_cov_list[4]), 0.,
662 0., 0., 0., 0., 0., static_cast<double>(twist_cov_list[5]) };
668 tf_odom_pub_->msg_.transforms[0].transform.translation.z = 0.0;
670 tf_odom_pub_->msg_.transforms[0].header.frame_id =
"odom";
void setVelocityRollingWindowSize(size_t velocity_rolling_window_size)
Velocity rolling window size setter.
void stopping(const ros::Time &)
Stops controller.
ros::Subscriber sub_command_four_wheel_steering_
double cmd_vel_timeout_
Timeout to consider cmd_vel commands old:
void cmdVelCallback(const geometry_msgs::Twist &command)
Velocity command callback.
std::string base_frame_id_
Frame to use for the robot base:
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
void updateCommand(const ros::Time &time, const ros::Duration &period)
Compute and publish command.
std::vector< hardware_interface::JointHandle > front_steering_joints_
std::vector< hardware_interface::JointHandle > rear_wheel_joints_
void update(const ros::Time &time, const ros::Duration &period)
Updates controller, i.e. computes the odometry and sets the new velocity commands.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
double getLinearX() const
linear velocity getter along X on the robot base link frame
CommandTwist command_struct_twist_
void updateOdometry(const ros::Time &time)
Update and publish odometry.
double getLinearAcceleration() const
linear acceleration getter
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Initialize controller.
std::vector< hardware_interface::JointHandle > rear_steering_joints_
void cmdFourWheelSteeringCallback(const four_wheel_steering_msgs::FourWheelSteering &command)
Velocity and steering command callback.
#define ROS_INFO_STREAM_NAMED(name, args)
bool enable_twist_cmd_
Whether the control is make with four_wheel_steering msg or twist msg:
double wheel_steering_y_offset_
#define ROS_DEBUG_STREAM_THROTTLE(period, args)
double getFrontSteerVel() const
front steering velocity getter
double limit(double &v, double v0, double v1, double dt)
Limit the velocity and acceleration.
double wheel_radius_
Wheel radius (assuming it's the same for the left and right wheels):
std::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
Odometry related:
bool update(const double &fl_speed, const double &fr_speed, const double &rl_speed, const double &rr_speed, double front_steering, double rear_steering, const ros::Time &time)
Updates the odometry class with latest wheels and steerings position.
std::vector< hardware_interface::JointHandle > front_wheel_joints_
Hardware handles:
bool getWheelNames(ros::NodeHandle &controller_nh, const std::string &wheel_param, std::vector< std::string > &wheel_names)
Get the wheel names from a wheel param.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Type const & getType() const
bool has_acceleration_limits
double getAngular() const
angular velocity getter
ros::Subscriber sub_command_
double getX() const
x position getter
double getRearSteerVel() const
rear steering velocity getter
bool getParam(const std::string &key, std::string &s) const
ros::Time last_state_publish_time_
std::shared_ptr< realtime_tools::RealtimePublisher< four_wheel_steering_msgs::FourWheelSteeringStamped > > odom_4ws_pub_
double getY() const
y position getter
void setWheelParams(double steering_track, double wheel_steering_y_offset, double wheel_radius, double wheel_base)
Sets the wheel parameters: radius and separation.
void setOdomPubFields(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Sets the odometry publishing fields.
bool enable_odom_tf_
Whether to publish odometry to tf or not:
#define ROS_DEBUG_STREAM(args)
void brake()
Brakes the wheels, i.e. sets the velocity to 0.
ros::Duration publish_period_
Odometry related:
bool getJointRadius(const std::string &joint_name, double &radius)
JointHandle getHandle(const std::string &name)
double getHeading() const
heading getter
Velocity command related:
std::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
const std::string & getNamespace() const
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
double getLinearY() const
linear velocity getter along Y on the robot base link frame
FourWheelSteeringController()
void starting(const ros::Time &time)
Starts controller.
realtime_tools::RealtimeBuffer< CommandTwist > command_twist_
#define ROS_ERROR_NAMED(name,...)
Command4ws command_struct_four_wheel_steering_
bool getDistanceBetweenJoints(const std::string &first_joint_name, const std::string &second_joint_name, double &distance)
double getLinear() const
linear velocity getter norm
SpeedLimiter limiter_ang_
CommandTwist last1_cmd_
Speed limiters:
void init(const ros::Time &time)
Initialize the odometry.
double track_
Wheel separation (or track), distance between left and right wheels (from the midpoint of the wheel w...
double wheel_base_
Wheel base (distance between front and rear wheel):
T clamp(T x, T min, T max)
double getLinearJerk() const
linear jerk getter
realtime_tools::RealtimeBuffer< Command4ws > command_four_wheel_steering_
FourWheelSteering command related:
SpeedLimiter limiter_lin_