43 #include <urdf/urdfdom_compatibility.h>
44 #include <urdf_parser/urdf_parser.h>
48 return std::sqrt(std::pow(vec1.x-vec2.x,2) +
49 std::pow(vec1.y-vec2.y,2) +
50 std::pow(vec1.z-vec2.z,2));
68 ROS_ERROR_STREAM(
"Link " << link->name <<
" does not have collision description. Add collision description for link to urdf.");
72 if (!link->collision->geometry)
74 ROS_ERROR_STREAM(
"Link " << link->name <<
" does not have collision geometry description. Add collision geometry description for link to urdf.");
85 static bool isCylinder(
const urdf::LinkConstSharedPtr& link)
92 if (link->collision->geometry->type != urdf::Geometry::CYLINDER)
94 ROS_DEBUG_STREAM(
"Link " << link->name <<
" does not have cylinder geometry");
106 static bool isSphere(
const urdf::LinkConstSharedPtr& link)
113 if (link->collision->geometry->type != urdf::Geometry::SPHERE)
115 ROS_DEBUG_STREAM(
"Link " << link->name <<
" does not have sphere geometry");
128 static bool getWheelRadius(
const urdf::LinkConstSharedPtr& wheel_link,
double& wheel_radius)
132 wheel_radius = (
static_cast<urdf::Cylinder*
>(wheel_link->collision->geometry.get()))->radius;
137 wheel_radius = (
static_cast<urdf::Sphere*
>(wheel_link->collision->geometry.get()))->radius;
141 ROS_ERROR_STREAM(
"Wheel link " << wheel_link->name <<
" is NOT modeled as a cylinder or sphere!");
150 , wheel_separation_(0.0)
152 , wheel_separation_multiplier_(1.0)
153 , left_wheel_radius_multiplier_(1.0)
154 , right_wheel_radius_multiplier_(1.0)
155 , cmd_vel_timeout_(0.5)
156 , allow_multiple_cmd_vel_publishers_(true)
157 , base_frame_id_(
"base_link")
158 , odom_frame_id_(
"odom")
159 , enable_odom_tf_(true)
160 , wheel_joints_size_(0)
161 , publish_cmd_(false)
162 , publish_wheel_joint_controller_state_(false)
170 const std::string complete_ns = controller_nh.
getNamespace();
171 std::size_t
id = complete_ns.find_last_of(
"/");
172 name_ = complete_ns.substr(
id + 1);
175 std::vector<std::string> left_wheel_names, right_wheel_names;
176 if (!
getWheelNames(controller_nh,
"left_wheel", left_wheel_names) ||
177 !
getWheelNames(controller_nh,
"right_wheel", right_wheel_names))
182 if (left_wheel_names.size() != right_wheel_names.size())
185 "#left wheels (" << left_wheel_names.size() <<
") != " <<
186 "#right wheels (" << right_wheel_names.size() <<
").");
199 controller_nh.
param(
"publish_rate", publish_rate, 50.0);
201 << publish_rate <<
"Hz.");
210 if (controller_nh.
hasParam(
"wheel_radius_multiplier"))
212 double wheel_radius_multiplier;
213 controller_nh.
getParam(
"wheel_radius_multiplier", wheel_radius_multiplier);
229 int velocity_rolling_window_size = 10;
230 controller_nh.
param(
"velocity_rolling_window_size", velocity_rolling_window_size, velocity_rolling_window_size);
232 << velocity_rolling_window_size <<
".");
287 right_wheel_names[0],
288 lookup_wheel_separation,
289 lookup_wheel_radius))
301 "Odometry params : wheel separation " << ws
302 <<
", left wheel radius " << lwr
303 <<
", right wheel radius " << rwr);
350 "Adding left wheel with joint name: " << left_wheel_names[i]
351 <<
" and right wheel with joint name: " << right_wheel_names[i]);
370 DiffDriveControllerConfig config;
375 config.publish_rate = publish_rate;
410 double left_pos = 0.0;
411 double right_pos = 0.0;
416 if (std::isnan(lp) || std::isnan(rp))
434 const geometry_msgs::Quaternion orientation(
443 odom_pub_->msg_.pose.pose.orientation = orientation;
452 geometry_msgs::TransformStamped& odom_frame =
tf_odom_pub_->msg_.transforms[0];
453 odom_frame.header.stamp = time;
456 odom_frame.transform.rotation = orientation;
464 const double dt = (time - curr_cmd.
stamp).toSec();
474 const double cmd_dt(period.
toSec());
492 const double vel_left = (curr_cmd.
lin - curr_cmd.
ang * ws / 2.0)/lwr;
493 const double vel_right = (curr_cmd.
lin + curr_cmd.
ang * ws / 2.0)/rwr;
524 const double vel = 0.0;
540 <<
" publishers. Only 1 publisher is allowed. Going to brake.");
545 if(!std::isfinite(
command.angular.z) || !std::isfinite(
command.linear.x))
556 "Added values to command. "
568 const std::string& wheel_param,
569 std::vector<std::string>& wheel_names)
572 if (!controller_nh.
getParam(wheel_param, wheel_list))
575 "Couldn't retrieve wheel param '" << wheel_param <<
"'.");
581 if (wheel_list.
size() == 0)
584 "Wheel param '" << wheel_param <<
"' is an empty list");
588 for (
int i = 0; i < wheel_list.
size(); ++i)
593 "Wheel param '" << wheel_param <<
"' #" << i <<
599 wheel_names.resize(wheel_list.
size());
600 for (
int i = 0; i < wheel_list.
size(); ++i)
602 wheel_names[i] =
static_cast<std::string
>(wheel_list[i]);
607 wheel_names.push_back(wheel_list);
612 "Wheel param '" << wheel_param <<
613 "' is neither a list of strings nor a string.");
621 const std::string& left_wheel_name,
622 const std::string& right_wheel_name,
623 bool lookup_wheel_separation,
624 bool lookup_wheel_radius)
626 if (!(lookup_wheel_separation || lookup_wheel_radius))
633 const std::string model_param_name =
"robot_description";
634 bool res = root_nh.
hasParam(model_param_name);
635 std::string robot_model_str=
"";
636 if (!res || !root_nh.
getParam(model_param_name,robot_model_str))
642 urdf::ModelInterfaceSharedPtr model(urdf::parseURDF(robot_model_str));
644 urdf::JointConstSharedPtr left_wheel_joint(model->getJoint(left_wheel_name));
645 urdf::JointConstSharedPtr right_wheel_joint(model->getJoint(right_wheel_name));
647 if (!left_wheel_joint)
650 <<
" couldn't be retrieved from model description");
654 if (!right_wheel_joint)
657 <<
" couldn't be retrieved from model description");
661 if (lookup_wheel_separation)
664 ROS_INFO_STREAM(
"left wheel to origin: " << left_wheel_joint->parent_to_joint_origin_transform.position.x <<
","
665 << left_wheel_joint->parent_to_joint_origin_transform.position.y <<
", "
666 << left_wheel_joint->parent_to_joint_origin_transform.position.z);
667 ROS_INFO_STREAM(
"right wheel to origin: " << right_wheel_joint->parent_to_joint_origin_transform.position.x <<
","
668 << right_wheel_joint->parent_to_joint_origin_transform.position.y <<
", "
669 << right_wheel_joint->parent_to_joint_origin_transform.position.z);
672 right_wheel_joint->parent_to_joint_origin_transform.position);
676 if (lookup_wheel_radius)
693 controller_nh.
getParam(
"pose_covariance_diagonal", pose_cov_list);
696 for (
int i = 0; i < pose_cov_list.
size(); ++i)
700 controller_nh.
getParam(
"twist_covariance_diagonal", twist_cov_list);
703 for (
int i = 0; i < twist_cov_list.
size(); ++i)
710 odom_pub_->msg_.pose.pose.position.z = 0;
712 static_cast<double>(pose_cov_list[0]), 0., 0., 0., 0., 0.,
713 0.,
static_cast<double>(pose_cov_list[1]), 0., 0., 0., 0.,
714 0., 0.,
static_cast<double>(pose_cov_list[2]), 0., 0., 0.,
715 0., 0., 0.,
static_cast<double>(pose_cov_list[3]), 0., 0.,
716 0., 0., 0., 0.,
static_cast<double>(pose_cov_list[4]), 0.,
717 0., 0., 0., 0., 0.,
static_cast<double>(pose_cov_list[5]) };
718 odom_pub_->msg_.twist.twist.linear.y = 0;
719 odom_pub_->msg_.twist.twist.linear.z = 0;
720 odom_pub_->msg_.twist.twist.angular.x = 0;
721 odom_pub_->msg_.twist.twist.angular.y = 0;
723 static_cast<double>(twist_cov_list[0]), 0., 0., 0., 0., 0.,
724 0.,
static_cast<double>(twist_cov_list[1]), 0., 0., 0., 0.,
725 0., 0.,
static_cast<double>(twist_cov_list[2]), 0., 0., 0.,
726 0., 0., 0.,
static_cast<double>(twist_cov_list[3]), 0., 0.,
727 0., 0., 0., 0.,
static_cast<double>(twist_cov_list[4]), 0.,
728 0., 0., 0., 0., 0.,
static_cast<double>(twist_cov_list[5]) };
731 tf_odom_pub_->msg_.transforms[0].transform.translation.z = 0.0;
766 double wheel_separation,
double left_wheel_radius,
double right_wheel_radius)
770 const double cmd_dt(period.
toSec());
773 const double vel_left_desired = (curr_cmd.
lin - curr_cmd.
ang * wheel_separation / 2.0) / left_wheel_radius;
774 const double vel_right_desired = (curr_cmd.
lin + curr_cmd.
ang * wheel_separation / 2.0) / right_wheel_radius;