volksbot_node.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, Osnabrueck University
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright notice,
9  * this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright notice,
11  * this list of conditions and the following disclaimer in the documentation
12  * and/or other materials provided with the distribution.
13  * * Neither the name of the Osnabrueck University nor the names of its
14  * contributors may be used to endorse or promote products derived from this
15  * software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <geometry_msgs/Twist.h>
31 #include <nav_msgs/Odometry.h>
33 #include <tf/transform_listener.h>
34 #include <sensor_msgs/JointState.h>
35 #include <ros/ros.h>
36 #include <ros/console.h>
37 
38 #include <string>
39 
40 #include "volksbot.h"
41 
42 class ROSComm : public Comm
43 {
44  public:
46  const ros::NodeHandle &n,
47  double sigma_x,
48  double sigma_theta,
49  double cov_x_y,
50  double cov_x_theta,
51  double cov_y_theta,
52  size_t num_wheels,
53  std::vector<std::string> joint_names) :
54  n_(n),
55  sigma_x_(sigma_x),
56  sigma_theta_(sigma_theta),
57  cov_x_y_(cov_x_y),
58  cov_x_theta_(cov_x_theta),
59  cov_y_theta_(cov_y_theta),
60  publish_tf_(false),
61  odom_pub_(n_.advertise<nav_msgs::Odometry> ("odom", 10)),
62  joint_pub_(n_.advertise<sensor_msgs::JointState> ("joint_states", 1)),
63  num_wheels_(num_wheels),
64  joint_names_(joint_names){ }
65 
66  virtual void send_odometry(double x, double y, double theta, double v_x,
67  double v_theta, double wheelpos_l, double wheelpos_r);
68 
69  void setTFPrefix(const std::string &tf_prefix);
70 
71  private:
72  void populateCovariance(nav_msgs::Odometry &msg, double v_x, double
73  v_theta);
74 
78  std::string tf_prefix_;
79 
83  size_t num_wheels_;
84  std::vector<std::string> joint_names_;
85 };
86 
87 void ROSComm::setTFPrefix(const std::string &tf_prefix)
88 {
89  tf_prefix_ = tf_prefix;
90 }
91 
92 void ROSComm::populateCovariance(nav_msgs::Odometry &msg, double v_x, double v_theta)
93 {
94  double odom_multiplier = 1.0;
95 
96  if (fabs(v_x) <= 1e-8 && fabs(v_theta) <= 1e-8)
97  {
98  //nav_msgs::Odometry has a 6x6 covariance matrix
99  msg.twist.covariance[0] = 1e-12;
100  msg.twist.covariance[35] = 1e-12;
101 
102  msg.twist.covariance[30] = 1e-12;
103  msg.twist.covariance[5] = 1e-12;
104  }
105  else
106  {
107  //nav_msgs::Odometry has a 6x6 covariance matrix
108  msg.twist.covariance[0] = odom_multiplier * pow(sigma_x_, 2);
109  msg.twist.covariance[35] = odom_multiplier * pow(sigma_theta_, 2);
110 
111  msg.twist.covariance[30] = odom_multiplier * cov_x_theta_;
112  msg.twist.covariance[5] = odom_multiplier * cov_x_theta_;
113  }
114 
115  msg.twist.covariance[7] = DBL_MAX;
116  msg.twist.covariance[14] = DBL_MAX;
117  msg.twist.covariance[21] = DBL_MAX;
118  msg.twist.covariance[28] = DBL_MAX;
119 
120  msg.pose.covariance = msg.twist.covariance;
121 
122  if (fabs(v_x) <= 1e-8 && fabs(v_theta) <= 1e-8)
123  {
124  msg.pose.covariance[7] = 1e-12;
125 
126  msg.pose.covariance[1] = 1e-12;
127  msg.pose.covariance[6] = 1e-12;
128 
129  msg.pose.covariance[31] = 1e-12;
130  msg.pose.covariance[11] = 1e-12;
131  }
132  else
133  {
134  msg.pose.covariance[7] = odom_multiplier * pow(sigma_x_, 2) * pow(sigma_theta_, 2);
135 
136  msg.pose.covariance[1] = odom_multiplier * cov_x_y_;
137  msg.pose.covariance[6] = odom_multiplier * cov_x_y_;
138 
139  msg.pose.covariance[31] = odom_multiplier * cov_y_theta_;
140  msg.pose.covariance[11] = odom_multiplier * cov_y_theta_;
141  }
142 }
143 
144 void ROSComm::send_odometry(double x, double y, double theta, double v_x, double v_theta, double wheelpos_l, double wheelpos_r)
145 {
146  nav_msgs::Odometry odom;
147  odom.header.frame_id = tf::resolve(tf_prefix_, "odom_combined");
148  odom.child_frame_id = tf::resolve(tf_prefix_, "base_footprint");
149 
150  odom.header.stamp = ros::Time::now();
151  odom.pose.pose.position.x = x;
152  odom.pose.pose.position.y = y;
153  odom.pose.pose.position.z = 0.0;
154  odom.pose.pose.orientation = tf::createQuaternionMsgFromYaw(theta);
155 
156  odom.twist.twist.linear.x = v_x;
157  odom.twist.twist.linear.y = 0.0;
158  odom.twist.twist.angular.z = v_theta;
159  populateCovariance(odom, v_x, v_theta);
160 
161  odom_pub_.publish(odom);
162 
163  if (publish_tf_)
164  {
165  geometry_msgs::TransformStamped odom_trans;
166  odom_trans.header.frame_id = tf::resolve(tf_prefix_, "odom_combined");
167  odom_trans.child_frame_id = tf::resolve(tf_prefix_, "base_footprint");
168 
169  odom_trans.header.stamp = ros::Time::now();
170  odom_trans.transform.translation.x = x;
171  odom_trans.transform.translation.y = y;
172  odom_trans.transform.translation.z = 0.0;
173  odom_trans.transform.rotation = tf::createQuaternionMsgFromYaw(theta);
174 
175  odom_broadcaster_.sendTransform(odom_trans);
176  }
177 
178  sensor_msgs::JointState joint_state;
179  joint_state.header.stamp = ros::Time::now();
180  joint_state.name.resize(num_wheels_);
181  joint_state.position.resize(num_wheels_);
182  joint_state.name = joint_names_;
183 
184  if(num_wheels_ == 6)
185  {
186  joint_state.position[0] = joint_state.position[1] = joint_state.position[2] = wheelpos_l;
187  joint_state.position[3] = joint_state.position[4] = joint_state.position[5] = wheelpos_r;
188  }
189  else
190  {
191  joint_state.position[0] = joint_state.position[1] = wheelpos_l;
192  joint_state.position[2] = joint_state.position[3] = wheelpos_r;
193  }
194 
195  joint_pub_.publish(joint_state);
196 }
197 
198 class ROSCall
199 {
200  public:
201  ROSCall(Volksbot &volksbot, double axis_length) :
202  volksbot_(volksbot),
203  axis_length_(axis_length),
204  last_cmd_vel_time_(0.0) { }
205  void velCallback(const geometry_msgs::Twist::ConstPtr& msg);
206  void cmd_velWatchdog(const ros::TimerEvent& event);
207 
208  private:
210  double axis_length_;
212 };
213 
214 void ROSCall::velCallback(const geometry_msgs::Twist::ConstPtr& msg)
215 {
216  last_cmd_vel_time_ = ros::Time::now();
217  double max_vel = volksbot_.get_max_vel();
218  double velocity = msg->linear.x;
219 
220  velocity = std::min(max_vel, velocity);
221  velocity = std::max(-max_vel, velocity);
222  volksbot_.set_wheel_speed(velocity - axis_length_ * msg->angular.z * 0.5, velocity + axis_length_ * msg->angular.z * 0.5);
223 }
224 
226 {
227  if (ros::Time::now() - last_cmd_vel_time_ > ros::Duration(0.6))
228  volksbot_.set_wheel_speed(0.0, 0.0);
229 }
230 
231 int main(int argc, char** argv)
232 {
233  ros::init(argc, argv, "volksbot");
234  ros::NodeHandle n;
235  ros::NodeHandle nh_ns("~");
236 
237  /* This is the wheel Radius for the odometry, accounting for some slip in the movement.
238  * therefor it's not the same as the one in the volksbot.urdf.xacro */
239  double wheel_radius;
240  nh_ns.param("wheel_radius", wheel_radius, 0.0985);
241  double axis_length;
242  nh_ns.param("axis_length", axis_length, 0.41);
243  int gear_ratio;
244  nh_ns.param("gear_ratio", gear_ratio, 74);
245  int max_vel_l;
246  nh_ns.param("max_vel_l", max_vel_l, 8250);
247  int max_vel_r;
248  nh_ns.param("max_vel_r", max_vel_r, 8400);
249  int max_acc_l;
250  nh_ns.param("max_acc_l", max_acc_l, 10000);
251  int max_acc_r;
252  nh_ns.param("max_acc_r", max_acc_r, 10000);
253  bool drive_backwards;
254  nh_ns.param("drive_backwards", drive_backwards, false);
255 
256  double turning_adaptation;
257  nh_ns.param("turning_adaptation", turning_adaptation, 0.95);
258 
259  int num_wheels;
260  // 4 or 6 wheels are supported
261  nh_ns.param("num_wheels", num_wheels, 6);
262  if(num_wheels != 4 && num_wheels != 6)
263  {
264  ROS_FATAL("Wrong configuration of the volksbot driver: Only four or six wheels are supported! See param \"num_wheels\".");
265  exit(1);
266  }
267 
268  std::vector<std::string> joint_names;
269  if(nh_ns.getParam("joint_names", joint_names))
270  {
271  if(num_wheels != joint_names.size())
272  {
273  ROS_FATAL("Wrong configuration of the volksbot driver: The number of joint names must equak the number of wheels!");
274  exit(1);
275  }
276  ROS_INFO("Using joint names from \"joint_names\" parameter list");
277  }
278  else if(num_wheels == 6)
279  {
280  ROS_INFO("Using default joint names for six wheels.");
281  // default values;
282  joint_names = {
283  "left_front_wheel_joint",
284  "left_middle_wheel_joint",
285  "left_rear_wheel_joint",
286  "right_front_wheel_joint",
287  "right_middle_wheel_joint",
288  "right_rear_wheel_joint"
289  };
290  }
291  else
292  {
293  // default values;
294  ROS_INFO("Using default joint names for four wheels.");
295  joint_names = {
296  "left_front_wheel_joint",
297  "left_rear_wheel_joint",
298  "right_front_wheel_joint",
299  "right_rear_wheel_joint"
300  };
301  }
302 
303  double sigma_x, sigma_theta, cov_x_y, cov_x_theta, cov_y_theta;
304  nh_ns.param("x_stddev", sigma_x, 0.002);
305  nh_ns.param("rotation_stddev", sigma_theta, 0.017);
306  nh_ns.param("cov_xy", cov_x_y, 0.0);
307  nh_ns.param("cov_xrotation", cov_x_theta, 0.0);
308  nh_ns.param("cov_yrotation", cov_y_theta, 0.0);
309 
310  ROSComm roscomm(n, sigma_x, sigma_theta, cov_x_y, cov_x_theta, cov_y_theta, num_wheels, joint_names);
311 
312  Volksbot volksbot(roscomm, wheel_radius, axis_length, turning_adaptation, gear_ratio, max_vel_l, max_vel_r, max_acc_l, max_acc_r, drive_backwards);
313 
314  bool publish_tf;
315  nh_ns.param("publish_tf", publish_tf, false);
316  std::string tf_prefix;
317  tf_prefix = tf::getPrefixParam(nh_ns);
318  roscomm.setTFPrefix(tf_prefix);
319 
320  ROSCall roscall(volksbot, axis_length);
321 
322  ros::Timer timer = n.createTimer(ros::Duration(0.1), &ROSCall::cmd_velWatchdog, &roscall);
323  ros::Subscriber cmd_vel_sub = n.subscribe("cmd_vel", 10, &ROSCall::velCallback, &roscall);
324 
325  while (ros::ok())
326  {
327  volksbot.odometry();
328  ros::spinOnce();
329  }
330 
331  return 0;
332 }
void velCallback(const geometry_msgs::Twist::ConstPtr &msg)
int main(int argc, char **argv)
#define ROS_FATAL(...)
std::string getPrefixParam(ros::NodeHandle &nh)
Definition: comm.h:33
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
double cov_x_theta_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
tf::TransformBroadcaster odom_broadcaster_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::NodeHandle n_
double cov_y_theta_
ros::Publisher joint_pub_
void populateCovariance(nav_msgs::Odometry &msg, double v_x, double v_theta)
std::string resolve(const std::string &prefix, const std::string &frame_name)
double sigma_theta_
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
void setTFPrefix(const std::string &tf_prefix)
#define ROS_INFO(...)
bool getParam(const std::string &key, std::string &s) const
double sigma_x_
bool publish_tf_
double cov_x_y_
void odometry()
Definition: volksbot.cpp:115
void cmd_velWatchdog(const ros::TimerEvent &event)
ROSCPP_DECL bool ok()
void sendTransform(const StampedTransform &transform)
double axis_length_
ros::Time last_cmd_vel_time_
ros::Publisher odom_pub_
ROSCall(Volksbot &volksbot, double axis_length)
Volksbot & volksbot_
std::string tf_prefix_
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
ROSComm(const ros::NodeHandle &n, double sigma_x, double sigma_theta, double cov_x_y, double cov_x_theta, double cov_y_theta, size_t num_wheels, std::vector< std::string > joint_names)
std::vector< std::string > joint_names_
size_t num_wheels_
static Time now()
virtual void send_odometry(double x, double y, double theta, double v_x, double v_theta, double wheelpos_l, double wheelpos_r)
ROSCPP_DECL void spinOnce()


volksbot_driver
Author(s): Jochen Sprickerhof
autogenerated on Tue Mar 1 2022 00:02:18