42 #include <boost/assign.hpp> 45 #include <urdf_parser/urdf_parser.h> 51 return std::sqrt(std::pow(vec1.x-vec2.x,2) +
52 std::pow(vec1.y-vec2.y,2) +
53 std::pow(vec1.z-vec2.z,2));
71 ROS_ERROR_STREAM(
"Link " << link->name <<
" does not have collision description. Add collision description for link to urdf.");
75 if (!link->collision->geometry)
77 ROS_ERROR_STREAM(
"Link " << link->name <<
" does not have collision geometry description. Add collision geometry description for link to urdf.");
81 if (link->collision->geometry->type != urdf::Geometry::CYLINDER)
83 ROS_ERROR_STREAM(
"Link " << link->name <<
" does not have cylinder geometry");
101 ROS_ERROR_STREAM(
"Wheel link " << wheel_link->name <<
" is NOT modeled as a cylinder!");
105 wheel_radius = (
static_cast<urdf::Cylinder*
>(wheel_link->collision->geometry.get()))->radius;
114 , wheel_separation_h_(0.0)
116 , wheel_separation_h_multiplier_(1.0)
117 , wheel_radius_multiplier_(1.0)
118 , steer_pos_multiplier_(1.0)
119 , cmd_vel_timeout_(0.5)
120 , allow_multiple_cmd_vel_publishers_(true)
121 , base_frame_id_(
"base_link")
122 , odom_frame_id_(
"odom")
123 , enable_odom_tf_(true)
124 , wheel_joints_size_(0)
137 VelIface *vel_joint_if = robot_hw->
get<VelIface>();
138 PosIface *pos_joint_if = robot_hw->
get<PosIface>();
140 const std::string complete_ns = controller_nh.
getNamespace();
142 std::size_t
id = complete_ns.find_last_of(
"/");
143 name_ = complete_ns.substr(
id + 1);
146 std::string rear_wheel_name =
"rear_wheel_joint";
147 controller_nh.
param(
"rear_wheel", rear_wheel_name, rear_wheel_name);
150 std::string front_steer_name =
"front_steer_joint";
151 controller_nh.
param(
"front_steer", front_steer_name, front_steer_name);
156 controller_nh.
param(
"publish_rate", publish_rate, 50.0);
158 << publish_rate <<
"Hz.");
175 int velocity_rolling_window_size = 10;
176 controller_nh.
param(
"velocity_rolling_window_size", velocity_rolling_window_size, velocity_rolling_window_size);
178 << velocity_rolling_window_size <<
".");
228 lookup_wheel_separation_h,
229 lookup_wheel_radius))
240 "Odometry params : wheel separation height " << ws_h
241 <<
", wheel radius " << wr);
248 "Adding the rear wheel with joint name: " << rear_wheel_name);
252 "Adding the front steer with joint name: " << front_steer_name);
255 "Adding the subscriber: cmd_vel");
274 if (std::isnan(wheel_pos) || std::isnan(steer_pos))
287 const geometry_msgs::Quaternion orientation(
296 odom_pub_->msg_.pose.pose.orientation = orientation;
305 geometry_msgs::TransformStamped& odom_frame =
tf_odom_pub_->msg_.transforms[0];
306 odom_frame.header.stamp = time;
309 odom_frame.transform.rotation = orientation;
317 const double dt = (time - curr_cmd.
stamp).toSec();
327 const double cmd_dt(period.
toSec());
359 const double steer_pos = 0.0;
360 const double wheel_vel = 0.0;
374 <<
" publishers. Only 1 publisher is allowed. Going to brake.");
384 "Added values to command. " 397 const std::string rear_wheel_name,
398 const std::string front_steer_name,
399 bool lookup_wheel_separation_h,
400 bool lookup_wheel_radius)
402 if (!(lookup_wheel_separation_h || lookup_wheel_radius))
409 const std::string model_param_name =
"robot_description";
410 bool res = root_nh.
hasParam(model_param_name);
411 std::string robot_model_str=
"";
412 if (!res || !root_nh.
getParam(model_param_name,robot_model_str))
423 if (lookup_wheel_separation_h)
426 if (!rear_wheel_joint)
429 <<
" couldn't be retrieved from model description");
433 if (!front_steer_joint)
436 <<
" couldn't be retrieved from model description");
441 << rear_wheel_joint->parent_to_joint_origin_transform.position.x <<
"," 442 << rear_wheel_joint->parent_to_joint_origin_transform.position.y <<
", " 443 << rear_wheel_joint->parent_to_joint_origin_transform.position.z);
446 << front_steer_joint->parent_to_joint_origin_transform.position.x <<
"," 447 << front_steer_joint->parent_to_joint_origin_transform.position.y <<
", " 448 << front_steer_joint->parent_to_joint_origin_transform.position.z);
451 rear_wheel_joint->parent_to_joint_origin_transform.position.x
452 - front_steer_joint->parent_to_joint_origin_transform.position.x);
457 if (lookup_wheel_radius)
475 controller_nh.
getParam(
"pose_covariance_diagonal", pose_cov_list);
478 for (
int i = 0; i < pose_cov_list.
size(); ++i)
482 controller_nh.
getParam(
"twist_covariance_diagonal", twist_cov_list);
485 for (
int i = 0; i < twist_cov_list.
size(); ++i)
492 odom_pub_->msg_.pose.pose.position.z = 0;
493 odom_pub_->msg_.pose.covariance = boost::assign::list_of
494 (static_cast<double>(pose_cov_list[0])) (0) (0) (0) (0) (0)
495 (0) (
static_cast<double>(pose_cov_list[1])) (0) (0) (0) (0)
496 (0) (0) (
static_cast<double>(pose_cov_list[2])) (0) (0) (0)
497 (0) (0) (0) (
static_cast<double>(pose_cov_list[3])) (0) (0)
498 (0) (0) (0) (0) (
static_cast<double>(pose_cov_list[4])) (0)
499 (0) (0) (0) (0) (0) (
static_cast<double>(pose_cov_list[5]));
500 odom_pub_->msg_.twist.twist.linear.y = 0;
501 odom_pub_->msg_.twist.twist.linear.z = 0;
502 odom_pub_->msg_.twist.twist.angular.x = 0;
503 odom_pub_->msg_.twist.twist.angular.y = 0;
504 odom_pub_->msg_.twist.covariance = boost::assign::list_of
505 (static_cast<double>(twist_cov_list[0])) (0) (0) (0) (0) (0)
506 (0) (
static_cast<double>(twist_cov_list[1])) (0) (0) (0) (0)
507 (0) (0) (
static_cast<double>(twist_cov_list[2])) (0) (0) (0)
508 (0) (0) (0) (
static_cast<double>(twist_cov_list[3])) (0) (0)
509 (0) (0) (0) (0) (
static_cast<double>(twist_cov_list[4])) (0)
510 (0) (0) (0) (0) (0) (
static_cast<double>(twist_cov_list[5]));
513 tf_odom_pub_->msg_.transforms[0].transform.translation.z = 0.0;
AckermannSteeringController()
void init(const ros::Time &time)
Initialize the odometry.
static bool getWheelRadius(const boost::shared_ptr< const urdf::Link > &wheel_link, double &wheel_radius)
diff_drive_controller::SpeedLimiter limiter_lin_
realtime_tools::RealtimeBuffer< Commands > command_
void starting(const ros::Time &time)
Starts controller.
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
void update(const ros::Time &time, const ros::Duration &period)
Updates controller, i.e. computes the odometry and sets the new velocity commands.
double wheel_radius_multiplier_
bool enable_odom_tf_
Whether to publish odometry to tf or not:
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool has_acceleration_limits
void brake()
Brakes the wheels, i.e. sets the velocity to 0.
void stopping(const ros::Time &)
Stops controller.
boost::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
Odometry related:
static bool isCylinder(const boost::shared_ptr< const urdf::Link > &link)
#define ROS_INFO_STREAM_NAMED(name, args)
hardware_interface::JointHandle front_steer_joint_
Type const & getType() const
double getAngular() const
angular velocity getter
std::string base_frame_id_
Frame to use for the robot base:
PLUGINLIB_EXPORT_CLASS(diff_drive_controller::DiffDriveController, controller_interface::ControllerBase)
void setWheelParams(double wheel_reparation_h, double wheel_radius)
Sets the wheel parameters: radius and separation.
double getHeading() const
heading getter
double steer_pos_multiplier_
ros::Duration publish_period_
Odometry related:
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Initialize controller.
double getLinear() const
linear velocity getter
bool setOdomParamsFromUrdf(ros::NodeHandle &root_nh, const std::string rear_wheel_name, const std::string front_steer_name, bool lookup_wheel_separation_h, bool lookup_wheel_radius)
Sets odometry parameters from the URDF, i.e. the wheel radius and separation.
double wheel_separation_h_multiplier_
Wheel separation and radius calibration multipliers:
static double euclideanOfVectors(const urdf::Vector3 &vec1, const urdf::Vector3 &vec2)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
uint32_t getNumPublishers() const
ros::Time last_state_publish_time_
const std::string & getNamespace() const
std::string odom_frame_id_
Frame to use for odometry and odom tf:
void updateOpenLoop(double linear, double angular, const ros::Time &time)
Updates the odometry class with latest velocity command.
bool allow_multiple_cmd_vel_publishers_
Whether to allow multiple publishers on cmd_vel topic or not:
diff_drive_controller::SpeedLimiter limiter_ang_
ros::Subscriber sub_command_
double getPosition() const
double cmd_vel_timeout_
Timeout to consider cmd_vel commands old:
double wheel_separation_h_
Wheel separation, wrt the midpoint of the wheel width:
hardware_interface::JointHandle rear_wheel_joint_
Hardware handles:
double getX() const
x position getter
void setCommand(double command)
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
#define ROS_INFO_STREAM(args)
Commands last1_cmd_
Speed limiters:
boost::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
bool getParam(const std::string &key, std::string &s) const
double getY() const
y position getter
#define ROS_ERROR_STREAM_THROTTLE_NAMED(rate, name, args)
#define ROS_ERROR_NAMED(name,...)
void setOdomPubFields(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Sets the odometry publishing fields.
Velocity command related:
bool hasParam(const std::string &key) const
#define ROS_ERROR_STREAM(args)
double limit(double &v, double v0, double v1, double dt)
double wheel_radius_
Wheel radius (assuming it's the same for the left and right wheels):
void cmdVelCallback(const geometry_msgs::Twist &command)
Velocity command callback.
void setVelocityRollingWindowSize(size_t velocity_rolling_window_size)
Velocity rolling window size setter.
bool update(double rear_wheel_pos, double front_steer_pos, const ros::Time &time)
Updates the odometry class with latest wheels position.