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  n_(n),
53  sigma_x_(sigma_x),
54  sigma_theta_(sigma_theta),
55  cov_x_y_(cov_x_y),
56  cov_x_theta_(cov_x_theta),
57  cov_y_theta_(cov_y_theta),
58  publish_tf_(false),
59  odom_pub_(n_.advertise<nav_msgs::Odometry> ("odom", 10)),
60  joint_pub_(n_.advertise<sensor_msgs::JointState> ("joint_states", 1)) { }
61  virtual void send_odometry(double x, double y, double theta, double v_x,
62  double v_theta, double wheelpos_l, double wheelpos_r);
63 
64  void setTFPrefix(const std::string &tf_prefix);
65 
66  private:
67  void populateCovariance(nav_msgs::Odometry &msg, double v_x, double
68  v_theta);
69 
73  std::string tf_prefix_;
74 
78 };
79 
80 void ROSComm::setTFPrefix(const std::string &tf_prefix)
81 {
82  tf_prefix_ = tf_prefix;
83 }
84 
85 void ROSComm::populateCovariance(nav_msgs::Odometry &msg, double v_x, double v_theta)
86 {
87  double odom_multiplier = 1.0;
88 
89  if (fabs(v_x) <= 1e-8 && fabs(v_theta) <= 1e-8)
90  {
91  //nav_msgs::Odometry has a 6x6 covariance matrix
92  msg.twist.covariance[0] = 1e-12;
93  msg.twist.covariance[35] = 1e-12;
94 
95  msg.twist.covariance[30] = 1e-12;
96  msg.twist.covariance[5] = 1e-12;
97  }
98  else
99  {
100  //nav_msgs::Odometry has a 6x6 covariance matrix
101  msg.twist.covariance[0] = odom_multiplier * pow(sigma_x_, 2);
102  msg.twist.covariance[35] = odom_multiplier * pow(sigma_theta_, 2);
103 
104  msg.twist.covariance[30] = odom_multiplier * cov_x_theta_;
105  msg.twist.covariance[5] = odom_multiplier * cov_x_theta_;
106  }
107 
108  msg.twist.covariance[7] = DBL_MAX;
109  msg.twist.covariance[14] = DBL_MAX;
110  msg.twist.covariance[21] = DBL_MAX;
111  msg.twist.covariance[28] = DBL_MAX;
112 
113  msg.pose.covariance = msg.twist.covariance;
114 
115  if (fabs(v_x) <= 1e-8 && fabs(v_theta) <= 1e-8)
116  {
117  msg.pose.covariance[7] = 1e-12;
118 
119  msg.pose.covariance[1] = 1e-12;
120  msg.pose.covariance[6] = 1e-12;
121 
122  msg.pose.covariance[31] = 1e-12;
123  msg.pose.covariance[11] = 1e-12;
124  }
125  else
126  {
127  msg.pose.covariance[7] = odom_multiplier * pow(sigma_x_, 2) * pow(sigma_theta_, 2);
128 
129  msg.pose.covariance[1] = odom_multiplier * cov_x_y_;
130  msg.pose.covariance[6] = odom_multiplier * cov_x_y_;
131 
132  msg.pose.covariance[31] = odom_multiplier * cov_y_theta_;
133  msg.pose.covariance[11] = odom_multiplier * cov_y_theta_;
134  }
135 }
136 
137 void ROSComm::send_odometry(double x, double y, double theta, double v_x, double v_theta, double wheelpos_l, double wheelpos_r)
138 {
139  nav_msgs::Odometry odom;
140  odom.header.frame_id = tf::resolve(tf_prefix_, "odom_combined");
141  odom.child_frame_id = tf::resolve(tf_prefix_, "base_footprint");
142 
143  odom.header.stamp = ros::Time::now();
144  odom.pose.pose.position.x = x;
145  odom.pose.pose.position.y = y;
146  odom.pose.pose.position.z = 0.0;
147  odom.pose.pose.orientation = tf::createQuaternionMsgFromYaw(theta);
148 
149  odom.twist.twist.linear.x = v_x;
150  odom.twist.twist.linear.y = 0.0;
151  odom.twist.twist.angular.z = v_theta;
152  populateCovariance(odom, v_x, v_theta);
153 
154  odom_pub_.publish(odom);
155 
156  if (publish_tf_)
157  {
158  geometry_msgs::TransformStamped odom_trans;
159  odom_trans.header.frame_id = tf::resolve(tf_prefix_, "odom_combined");
160  odom_trans.child_frame_id = tf::resolve(tf_prefix_, "base_footprint");
161 
162  odom_trans.header.stamp = ros::Time::now();
163  odom_trans.transform.translation.x = x;
164  odom_trans.transform.translation.y = y;
165  odom_trans.transform.translation.z = 0.0;
166  odom_trans.transform.rotation = tf::createQuaternionMsgFromYaw(theta);
167 
168  odom_broadcaster_.sendTransform(odom_trans);
169  }
170 
171  sensor_msgs::JointState joint_state;
172  joint_state.header.stamp = ros::Time::now();
173  joint_state.name.resize(6);
174  joint_state.position.resize(6);
175  joint_state.name[0] = "left_front_wheel_joint";
176  joint_state.name[1] = "left_middle_wheel_joint";
177  joint_state.name[2] = "left_rear_wheel_joint";
178  joint_state.name[3] = "right_front_wheel_joint";
179  joint_state.name[4] = "right_middle_wheel_joint";
180  joint_state.name[5] = "right_rear_wheel_joint";
181 
182  joint_state.position[0] = joint_state.position[1] = joint_state.position[2] = wheelpos_l;
183  joint_state.position[3] = joint_state.position[4] = joint_state.position[5] = wheelpos_r;
184 
185  joint_pub_.publish(joint_state);
186 }
187 
188 class ROSCall
189 {
190  public:
191  ROSCall(Volksbot &volksbot, double axis_length) :
192  volksbot_(volksbot),
193  axis_length_(axis_length),
194  last_cmd_vel_time_(0.0) { }
195  void velCallback(const geometry_msgs::Twist::ConstPtr& msg);
196  void cmd_velWatchdog(const ros::TimerEvent& event);
197 
198  private:
200  double axis_length_;
202 };
203 
204 void ROSCall::velCallback(const geometry_msgs::Twist::ConstPtr& msg)
205 {
206  last_cmd_vel_time_ = ros::Time::now();
207  double max_vel = volksbot_.get_max_vel();
208  double velocity = msg->linear.x;
209 
210  velocity = std::min(max_vel, velocity);
211  velocity = std::max(-max_vel, velocity);
212  volksbot_.set_wheel_speed(velocity - axis_length_ * msg->angular.z * 0.5, velocity + axis_length_ * msg->angular.z * 0.5);
213 }
214 
216 {
217  if (ros::Time::now() - last_cmd_vel_time_ > ros::Duration(0.6))
218  volksbot_.set_wheel_speed(0.0, 0.0);
219 }
220 
221 int main(int argc, char** argv)
222 {
223  ros::init(argc, argv, "volksbot");
224  ros::NodeHandle n;
225  ros::NodeHandle nh_ns("~");
226 
227  /* This is the wheel Radius for the odometry, accounting for some slip in the movement.
228  * therefor it's not the same as the one in the volksbot.urdf.xacro */
229  double wheel_radius;
230  nh_ns.param("wheel_radius", wheel_radius, 0.0985);
231  double axis_length;
232  nh_ns.param("axis_length", axis_length, 0.41);
233  int gear_ratio;
234  nh_ns.param("gear_ratio", gear_ratio, 74);
235  int max_vel_l;
236  nh_ns.param("max_vel_l", max_vel_l, 8250);
237  int max_vel_r;
238  nh_ns.param("max_vel_r", max_vel_r, 8400);
239  int max_acc_l;
240  nh_ns.param("max_acc_l", max_acc_l, 10000);
241  int max_acc_r;
242  nh_ns.param("max_acc_r", max_acc_r, 10000);
243  bool drive_backwards;
244  nh_ns.param("drive_backwards", drive_backwards, false);
245 
246  double turning_adaptation;
247  nh_ns.param("turning_adaptation", turning_adaptation, 0.95);
248 
249  double sigma_x, sigma_theta, cov_x_y, cov_x_theta, cov_y_theta;
250  nh_ns.param("x_stddev", sigma_x, 0.002);
251  nh_ns.param("rotation_stddev", sigma_theta, 0.017);
252  nh_ns.param("cov_xy", cov_x_y, 0.0);
253  nh_ns.param("cov_xrotation", cov_x_theta, 0.0);
254  nh_ns.param("cov_yrotation", cov_y_theta, 0.0);
255 
256  ROSComm roscomm(n, sigma_x, sigma_theta, cov_x_y, cov_x_theta, cov_y_theta);
257 
258  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);
259 
260  bool publish_tf;
261  nh_ns.param("publish_tf", publish_tf, false);
262  std::string tf_prefix;
263  tf_prefix = tf::getPrefixParam(nh_ns);
264  roscomm.setTFPrefix(tf_prefix);
265 
266  ROSCall roscall(volksbot, axis_length);
267 
268  ros::Timer timer = n.createTimer(ros::Duration(0.1), &ROSCall::cmd_velWatchdog, &roscall);
269  ros::Subscriber cmd_vel_sub = n.subscribe("cmd_vel", 10, &ROSCall::velCallback, &roscall);
270 
271  while (ros::ok())
272  {
273  volksbot.odometry();
274  ros::spinOnce();
275  }
276 
277  return 0;
278 }
void velCallback(const geometry_msgs::Twist::ConstPtr &msg)
int main(int argc, char **argv)
void publish(const boost::shared_ptr< M > &message) const
std::string getPrefixParam(ros::NodeHandle &nh)
Definition: comm.h:33
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)
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::string resolve(const std::string &prefix, const std::string &frame_name)
double sigma_theta_
void setTFPrefix(const std::string &tf_prefix)
double sigma_x_
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool publish_tf_
double cov_x_y_
void odometry()
Definition: volksbot.cpp:115
void cmd_velWatchdog(const ros::TimerEvent &event)
ROSCPP_DECL bool ok()
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void sendTransform(const StampedTransform &transform)
double axis_length_
ros::Time last_cmd_vel_time_
TFSIMD_FORCE_INLINE const tfScalar & x() const
ros::Publisher odom_pub_
ROSCall(Volksbot &volksbot, double axis_length)
Volksbot & volksbot_
std::string tf_prefix_
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
static Time now()
ROSComm(const ros::NodeHandle &n, double sigma_x, double sigma_theta, double cov_x_y, double cov_x_theta, double cov_y_theta)
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 Sun Jul 21 2019 04:00:45