42 #include <urdf/urdfdom_compatibility.h> 43 #include <urdf_parser/urdf_parser.h> 47 return std::sqrt(std::pow(vec1.x-vec2.x,2) +
48 std::pow(vec1.y-vec2.y,2) +
49 std::pow(vec1.z-vec2.z,2));
67 ROS_ERROR_STREAM(
"Link " << link->name <<
" does not have collision description. Add collision description for link to urdf.");
71 if (!link->collision->geometry)
73 ROS_ERROR_STREAM(
"Link " << link->name <<
" does not have collision geometry description. Add collision geometry description for link to urdf.");
84 static bool isCylinder(
const urdf::LinkConstSharedPtr& link)
91 if (link->collision->geometry->type != urdf::Geometry::CYLINDER)
93 ROS_DEBUG_STREAM(
"Link " << link->name <<
" does not have cylinder geometry");
105 static bool isSphere(
const urdf::LinkConstSharedPtr& link)
112 if (link->collision->geometry->type != urdf::Geometry::SPHERE)
114 ROS_DEBUG_STREAM(
"Link " << link->name <<
" does not have sphere geometry");
127 static bool getWheelRadius(
const urdf::LinkConstSharedPtr& wheel_link,
double& wheel_radius)
131 wheel_radius = (
static_cast<urdf::Cylinder*
>(wheel_link->collision->geometry.get()))->radius;
136 wheel_radius = (
static_cast<urdf::Sphere*
>(wheel_link->collision->geometry.get()))->radius;
140 ROS_ERROR_STREAM(
"Wheel link " << wheel_link->name <<
" is NOT modeled as a cylinder or sphere!");
149 , wheel_separation_(0.0)
151 , wheel_separation_multiplier_(1.0)
152 , left_wheel_radius_multiplier_(1.0)
153 , right_wheel_radius_multiplier_(1.0)
154 , cmd_vel_timeout_(0.5)
155 , allow_multiple_cmd_vel_publishers_(true)
156 , base_frame_id_(
"base_link")
157 , odom_frame_id_(
"odom")
158 , enable_odom_tf_(true)
159 , wheel_joints_size_(0)
160 , publish_cmd_(false)
161 , publish_wheel_joint_controller_state_(false)
169 const std::string complete_ns = controller_nh.
getNamespace();
170 std::size_t
id = complete_ns.find_last_of(
"/");
171 name_ = complete_ns.substr(
id + 1);
174 std::vector<std::string> left_wheel_names, right_wheel_names;
175 if (!
getWheelNames(controller_nh,
"left_wheel", left_wheel_names) ||
176 !
getWheelNames(controller_nh,
"right_wheel", right_wheel_names))
181 if (left_wheel_names.size() != right_wheel_names.size())
184 "#left wheels (" << left_wheel_names.size() <<
") != " <<
185 "#right wheels (" << right_wheel_names.size() <<
").");
198 controller_nh.
param(
"publish_rate", publish_rate, 50.0);
200 << publish_rate <<
"Hz.");
209 if (controller_nh.
hasParam(
"wheel_radius_multiplier"))
211 double wheel_radius_multiplier;
212 controller_nh.
getParam(
"wheel_radius_multiplier", wheel_radius_multiplier);
228 int velocity_rolling_window_size = 10;
229 controller_nh.
param(
"velocity_rolling_window_size", velocity_rolling_window_size, velocity_rolling_window_size);
231 << velocity_rolling_window_size <<
".");
286 right_wheel_names[0],
287 lookup_wheel_separation,
288 lookup_wheel_radius))
300 "Odometry params : wheel separation " << ws
301 <<
", left wheel radius " << lwr
302 <<
", right wheel radius " << rwr);
349 "Adding left wheel with joint name: " << left_wheel_names[i]
350 <<
" and right wheel with joint name: " << right_wheel_names[i]);
369 DiffDriveControllerConfig config;
374 config.publish_rate = publish_rate;
380 dyn_reconf_server_mutex_.lock();
382 dyn_reconf_server_mutex_.unlock();
408 double left_pos = 0.0;
409 double right_pos = 0.0;
414 if (std::isnan(lp) || std::isnan(rp))
432 const geometry_msgs::Quaternion orientation(
441 odom_pub_->msg_.pose.pose.orientation = orientation;
450 geometry_msgs::TransformStamped& odom_frame =
tf_odom_pub_->msg_.transforms[0];
451 odom_frame.header.stamp = time;
454 odom_frame.transform.rotation = orientation;
462 const double dt = (time - curr_cmd.
stamp).toSec();
472 const double cmd_dt(period.
toSec());
490 const double vel_left = (curr_cmd.
lin - curr_cmd.
ang * ws / 2.0)/lwr;
491 const double vel_right = (curr_cmd.
lin + curr_cmd.
ang * ws / 2.0)/rwr;
522 const double vel = 0.0;
538 <<
" publishers. Only 1 publisher is allowed. Going to brake.");
543 if(!std::isfinite(command.angular.z) || !std::isfinite(command.angular.x))
554 "Added values to command. " 566 const std::string& wheel_param,
567 std::vector<std::string>& wheel_names)
570 if (!controller_nh.
getParam(wheel_param, wheel_list))
573 "Couldn't retrieve wheel param '" << wheel_param <<
"'.");
579 if (wheel_list.
size() == 0)
582 "Wheel param '" << wheel_param <<
"' is an empty list");
586 for (
int i = 0; i < wheel_list.
size(); ++i)
591 "Wheel param '" << wheel_param <<
"' #" << i <<
597 wheel_names.resize(wheel_list.
size());
598 for (
int i = 0; i < wheel_list.
size(); ++i)
600 wheel_names[i] =
static_cast<std::string
>(wheel_list[i]);
605 wheel_names.push_back(wheel_list);
610 "Wheel param '" << wheel_param <<
611 "' is neither a list of strings nor a string.");
619 const std::string& left_wheel_name,
620 const std::string& right_wheel_name,
621 bool lookup_wheel_separation,
622 bool lookup_wheel_radius)
624 if (!(lookup_wheel_separation || lookup_wheel_radius))
631 const std::string model_param_name =
"robot_description";
632 bool res = root_nh.
hasParam(model_param_name);
633 std::string robot_model_str=
"";
634 if (!res || !root_nh.
getParam(model_param_name,robot_model_str))
640 urdf::ModelInterfaceSharedPtr model(urdf::parseURDF(robot_model_str));
642 urdf::JointConstSharedPtr left_wheel_joint(model->getJoint(left_wheel_name));
643 urdf::JointConstSharedPtr right_wheel_joint(model->getJoint(right_wheel_name));
645 if (lookup_wheel_separation)
648 if (!left_wheel_joint)
651 <<
" couldn't be retrieved from model description");
655 if (!right_wheel_joint)
658 <<
" couldn't be retrieved from model description");
662 ROS_INFO_STREAM(
"left wheel to origin: " << left_wheel_joint->parent_to_joint_origin_transform.position.x <<
"," 663 << left_wheel_joint->parent_to_joint_origin_transform.position.y <<
", " 664 << left_wheel_joint->parent_to_joint_origin_transform.position.z);
665 ROS_INFO_STREAM(
"right wheel to origin: " << right_wheel_joint->parent_to_joint_origin_transform.position.x <<
"," 666 << right_wheel_joint->parent_to_joint_origin_transform.position.y <<
", " 667 << right_wheel_joint->parent_to_joint_origin_transform.position.z);
670 right_wheel_joint->parent_to_joint_origin_transform.position);
674 if (lookup_wheel_radius)
691 controller_nh.
getParam(
"pose_covariance_diagonal", pose_cov_list);
694 for (
int i = 0; i < pose_cov_list.
size(); ++i)
698 controller_nh.
getParam(
"twist_covariance_diagonal", twist_cov_list);
701 for (
int i = 0; i < twist_cov_list.
size(); ++i)
708 odom_pub_->msg_.pose.pose.position.z = 0;
710 static_cast<double>(pose_cov_list[0]), 0., 0., 0., 0., 0.,
711 0., static_cast<double>(pose_cov_list[1]), 0., 0., 0., 0.,
712 0., 0.,
static_cast<double>(pose_cov_list[2]), 0., 0., 0.,
713 0., 0., 0., static_cast<double>(pose_cov_list[3]), 0., 0.,
714 0., 0., 0., 0.,
static_cast<double>(pose_cov_list[4]), 0.,
715 0., 0., 0., 0., 0., static_cast<double>(pose_cov_list[5]) };
716 odom_pub_->msg_.twist.twist.linear.y = 0;
717 odom_pub_->msg_.twist.twist.linear.z = 0;
718 odom_pub_->msg_.twist.twist.angular.x = 0;
719 odom_pub_->msg_.twist.twist.angular.y = 0;
721 static_cast<double>(twist_cov_list[0]), 0., 0., 0., 0., 0.,
722 0., static_cast<double>(twist_cov_list[1]), 0., 0., 0., 0.,
723 0., 0.,
static_cast<double>(twist_cov_list[2]), 0., 0., 0.,
724 0., 0., 0., static_cast<double>(twist_cov_list[3]), 0., 0.,
725 0., 0., 0., 0.,
static_cast<double>(twist_cov_list[4]), 0.,
726 0., 0., 0., 0., 0., static_cast<double>(twist_cov_list[5]) };
729 tf_odom_pub_->msg_.transforms[0].transform.translation.z = 0.0;
764 double wheel_separation,
double left_wheel_radius,
double right_wheel_radius)
768 const double cmd_dt(period.
toSec());
771 const double vel_left_desired = (curr_cmd.
lin - curr_cmd.
ang * wheel_separation / 2.0) / left_wheel_radius;
772 const double vel_right_desired = (curr_cmd.
lin + curr_cmd.
ang * wheel_separation / 2.0) / right_wheel_radius;
realtime_tools::RealtimeBuffer< Commands > command_
bool allow_multiple_cmd_vel_publishers_
Whether to allow multiple publishers on cmd_vel topic or not:
bool init(hardware_interface::VelocityJointInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Initialize controller.
double wheel_separation_
Wheel separation, wrt the midpoint of the wheel width:
void updateDynamicParams()
Update the dynamic parameters in the RT loop.
double wheel_separation_multiplier
std::vector< hardware_interface::JointHandle > left_wheel_joints_
Hardware handles:
static bool hasCollisionGeometry(const urdf::LinkConstSharedPtr &link)
Velocity command related:
double vel_right_desired_previous_
bool update(double left_pos, double right_pos, const ros::Time &time)
Updates the odometry class with latest wheels position.
#define ROS_DEBUG_STREAM_NAMED(name, args)
double wheel_radius_
Wheel radius (assuming it's the same for the left and right wheels):
#define ROS_ERROR_STREAM_NAMED(name, args)
static bool getWheelRadius(const urdf::LinkConstSharedPtr &wheel_link, double &wheel_radius)
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
std::string odom_frame_id_
Frame to use for odometry and odom tf:
static bool isCylinder(const urdf::LinkConstSharedPtr &link)
void brake()
Brakes the wheels, i.e. sets the velocity to 0.
uint32_t getNumPublishers() const
size_t wheel_joints_size_
Number of wheel joints:
#define ROS_INFO_STREAM_NAMED(name, args)
boost::recursive_mutex dyn_reconf_server_mutex_
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.
double getY() const
y position getter
double getAngular() const
angular velocity getter
#define ROS_ERROR_STREAM_THROTTLE_NAMED(period, name, args)
std::shared_ptr< realtime_tools::RealtimePublisher< control_msgs::JointTrajectoryControllerState > > controller_state_pub_
Controller state publisher.
std::vector< double > vel_left_previous_
Previous velocities from the encoders:
double right_wheel_radius_multiplier
std::vector< double > vel_right_previous_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Type const & getType() const
static bool isSphere(const urdf::LinkConstSharedPtr &link)
std::vector< hardware_interface::JointHandle > right_wheel_joints_
std::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
Odometry related:
double getHeading() const
heading getter
#define ROS_WARN_THROTTLE(period,...)
void starting(const ros::Time &time)
Starts controller.
double vel_left_desired_previous_
Previous velocities from the encoders:
bool getParam(const std::string &key, std::string &s) const
std::shared_ptr< realtime_tools::RealtimePublisher< geometry_msgs::TwistStamped > > cmd_vel_pub_
Publish executed commands.
void init(const ros::Time &time)
Initialize the odometry.
void cmdVelCallback(const geometry_msgs::Twist &command)
Velocity command callback.
ros::Time last_state_publish_time_
ros::Subscriber sub_command_
void setWheelParams(double wheel_separation, double left_wheel_radius, double right_wheel_radius)
Sets the wheel parameters: radius and separation.
void update(const ros::Time &time, const ros::Duration &period)
Updates controller, i.e. computes the odometry and sets the new velocity commands.
realtime_tools::RealtimeBuffer< DynamicParams > dynamic_params_
#define ROS_DEBUG_STREAM(args)
bool publish_wheel_joint_controller_state_
Publish wheel data:
void setVelocityRollingWindowSize(size_t velocity_rolling_window_size)
Velocity rolling window size setter.
bool hasParam(const std::string &key) const
double right_wheel_radius_multiplier_
ros::Duration publish_period_
Odometry related:
JointHandle getHandle(const std::string &name)
double left_wheel_radius_multiplier
void publishWheelData(const ros::Time &time, const ros::Duration &period, Commands &curr_cmd, double wheel_separation, double left_wheel_radius, double right_wheel_radius)
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
#define ROS_INFO_STREAM(args)
const std::string & getNamespace() const
double getLinear() const
linear velocity getter
static double euclideanOfVectors(const urdf::Vector3 &vec1, const urdf::Vector3 &vec2)
bool publish_cmd_
Publish limited velocity:
SpeedLimiter limiter_lin_
std::shared_ptr< ReconfigureServer > dyn_reconf_server_
void updateOpenLoop(double linear, double angular, const ros::Time &time)
Updates the odometry class with latest velocity command.
double cmd_vel_timeout_
Timeout to consider cmd_vel commands old:
#define ROS_ERROR_NAMED(name,...)
SpeedLimiter limiter_ang_
bool setOdomParamsFromUrdf(ros::NodeHandle &root_nh, const std::string &left_wheel_name, const std::string &right_wheel_name, bool lookup_wheel_separation, bool lookup_wheel_radius)
Sets odometry parameters from the URDF, i.e. the wheel radius and separation.
double getX() const
x position getter
double left_wheel_radius_multiplier_
bool enable_odom_tf_
Whether to publish odometry to tf or not:
Commands last1_cmd_
Speed limiters:
#define ROS_ERROR_STREAM(args)
void reconfCallback(DiffDriveControllerConfig &config, uint32_t)
Callback for dynamic_reconfigure server.
std::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
void setOdomPubFields(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Sets the odometry publishing fields.
double limit(double &v, double v0, double v1, double dt)
Limit the velocity and acceleration.
void stopping(const ros::Time &)
Stops controller.
double wheel_separation_multiplier_
Wheel separation and radius calibration multipliers:
std::string base_frame_id_
Frame to use for the robot base: