42 #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));
58 static bool isCylinder(
const urdf::LinkConstSharedPtr& link)
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.");
78 if (link->collision->geometry->type != urdf::Geometry::CYLINDER)
80 ROS_ERROR_STREAM(
"Link " << link->name <<
" does not have cylinder geometry");
94 static bool getWheelRadius(
const urdf::LinkConstSharedPtr& wheel_link,
double& wheel_radius)
98 ROS_ERROR_STREAM(
"Wheel link " << wheel_link->name <<
" is NOT modeled as a cylinder!");
102 wheel_radius = (
static_cast<urdf::Cylinder*
>(wheel_link->collision->geometry.get()))->radius;
111 , wheel_separation_h_(0.0)
113 , wheel_separation_h_multiplier_(1.0)
114 , wheel_radius_multiplier_(1.0)
115 , steer_pos_multiplier_(1.0)
116 , cmd_vel_timeout_(0.5)
117 , allow_multiple_cmd_vel_publishers_(true)
118 , base_frame_id_(
"base_link")
119 , odom_frame_id_(
"odom")
120 , enable_odom_tf_(true)
121 , wheel_joints_size_(0)
134 VelIface *vel_joint_if = robot_hw->
get<VelIface>();
135 PosIface *pos_joint_if = robot_hw->
get<PosIface>();
137 const std::string complete_ns = controller_nh.
getNamespace();
139 std::size_t
id = complete_ns.find_last_of(
"/");
140 name_ = complete_ns.substr(
id + 1);
143 std::string rear_wheel_name =
"rear_wheel_joint";
144 controller_nh.
param(
"rear_wheel", rear_wheel_name, rear_wheel_name);
147 std::string front_steer_name =
"front_steer_joint";
148 controller_nh.
param(
"front_steer", front_steer_name, front_steer_name);
153 controller_nh.
param(
"publish_rate", publish_rate, 50.0);
155 << publish_rate <<
"Hz.");
172 int velocity_rolling_window_size = 10;
173 controller_nh.
param(
"velocity_rolling_window_size", velocity_rolling_window_size, velocity_rolling_window_size);
175 << velocity_rolling_window_size <<
".");
225 lookup_wheel_separation_h,
226 lookup_wheel_radius))
237 "Odometry params : wheel separation height " << ws_h
238 <<
", wheel radius " << wr);
245 "Adding the rear wheel with joint name: " << rear_wheel_name);
249 "Adding the front steer with joint name: " << front_steer_name);
252 "Adding the subscriber: cmd_vel");
271 if (std::isnan(wheel_pos) || std::isnan(steer_pos))
284 const geometry_msgs::Quaternion orientation(
293 odom_pub_->msg_.pose.pose.orientation = orientation;
302 geometry_msgs::TransformStamped& odom_frame =
tf_odom_pub_->msg_.transforms[0];
303 odom_frame.header.stamp = time;
306 odom_frame.transform.rotation = orientation;
314 const double dt = (time - curr_cmd.
stamp).toSec();
324 const double cmd_dt(period.
toSec());
356 const double steer_pos = 0.0;
357 const double wheel_vel = 0.0;
371 <<
" publishers. Only 1 publisher is allowed. Going to brake.");
381 "Added values to command. "
394 const std::string rear_wheel_name,
395 const std::string front_steer_name,
396 bool lookup_wheel_separation_h,
397 bool lookup_wheel_radius)
399 if (!(lookup_wheel_separation_h || lookup_wheel_radius))
406 const std::string model_param_name =
"robot_description";
407 bool res = root_nh.
hasParam(model_param_name);
408 std::string robot_model_str=
"";
409 if (!res || !root_nh.
getParam(model_param_name,robot_model_str))
415 urdf::ModelInterfaceSharedPtr model(urdf::parseURDF(robot_model_str));
417 urdf::JointConstSharedPtr rear_wheel_joint(model->getJoint(rear_wheel_name));
418 urdf::JointConstSharedPtr front_steer_joint(model->getJoint(front_steer_name));
420 if (lookup_wheel_separation_h)
423 if (!rear_wheel_joint)
426 <<
" couldn't be retrieved from model description");
430 if (!front_steer_joint)
433 <<
" couldn't be retrieved from model description");
438 << rear_wheel_joint->parent_to_joint_origin_transform.position.x <<
","
439 << rear_wheel_joint->parent_to_joint_origin_transform.position.y <<
", "
440 << rear_wheel_joint->parent_to_joint_origin_transform.position.z);
443 << front_steer_joint->parent_to_joint_origin_transform.position.x <<
","
444 << front_steer_joint->parent_to_joint_origin_transform.position.y <<
", "
445 << front_steer_joint->parent_to_joint_origin_transform.position.z);
448 rear_wheel_joint->parent_to_joint_origin_transform.position.x
449 - front_steer_joint->parent_to_joint_origin_transform.position.x);
454 if (lookup_wheel_radius)
472 controller_nh.
getParam(
"pose_covariance_diagonal", pose_cov_list);
475 for (
int i = 0; i < pose_cov_list.
size(); ++i)
479 controller_nh.
getParam(
"twist_covariance_diagonal", twist_cov_list);
482 for (
int i = 0; i < twist_cov_list.
size(); ++i)
489 odom_pub_->msg_.pose.pose.position.z = 0;
491 static_cast<double>(pose_cov_list[0]), 0., 0., 0., 0., 0.,
492 0.,
static_cast<double>(pose_cov_list[1]), 0., 0., 0., 0.,
493 0., 0.,
static_cast<double>(pose_cov_list[2]), 0., 0., 0.,
494 0., 0., 0.,
static_cast<double>(pose_cov_list[3]), 0., 0.,
495 0., 0., 0., 0.,
static_cast<double>(pose_cov_list[4]), 0.,
496 0., 0., 0., 0., 0.,
static_cast<double>(pose_cov_list[5]) };
497 odom_pub_->msg_.twist.twist.linear.y = 0;
498 odom_pub_->msg_.twist.twist.linear.z = 0;
499 odom_pub_->msg_.twist.twist.angular.x = 0;
500 odom_pub_->msg_.twist.twist.angular.y = 0;
502 static_cast<double>(twist_cov_list[0]), 0., 0., 0., 0., 0.,
503 0.,
static_cast<double>(twist_cov_list[1]), 0., 0., 0., 0.,
504 0., 0.,
static_cast<double>(twist_cov_list[2]), 0., 0., 0.,
505 0., 0., 0.,
static_cast<double>(twist_cov_list[3]), 0., 0.,
506 0., 0., 0., 0.,
static_cast<double>(twist_cov_list[4]), 0.,
507 0., 0., 0., 0., 0.,
static_cast<double>(twist_cov_list[5]) };
510 tf_odom_pub_->msg_.transforms[0].transform.translation.z = 0.0;