00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <geometry_msgs/Twist.h>
00031 #include <nav_msgs/Odometry.h>
00032 #include <tf/transform_broadcaster.h>
00033 #include <tf/transform_listener.h>
00034 #include <sensor_msgs/JointState.h>
00035 #include <ros/ros.h>
00036 #include <ros/console.h>
00037
00038 #include <string>
00039
00040 #include "volksbot.h"
00041
00042 class ROSComm : public Comm
00043 {
00044 public:
00045 ROSComm(
00046 const ros::NodeHandle &n,
00047 double sigma_x,
00048 double sigma_theta,
00049 double cov_x_y,
00050 double cov_x_theta,
00051 double cov_y_theta) :
00052 n_(n),
00053 sigma_x_(sigma_x),
00054 sigma_theta_(sigma_theta),
00055 cov_x_y_(cov_x_y),
00056 cov_x_theta_(cov_x_theta),
00057 cov_y_theta_(cov_y_theta),
00058 publish_tf_(false),
00059 odom_pub_(n_.advertise<nav_msgs::Odometry> ("odom", 10)),
00060 joint_pub_(n_.advertise<sensor_msgs::JointState> ("joint_states", 1)) { }
00061 virtual void send_odometry(double x, double y, double theta, double v_x,
00062 double v_theta, double wheelpos_l, double wheelpos_r);
00063
00064 void setTFPrefix(const std::string &tf_prefix);
00065
00066 private:
00067 void populateCovariance(nav_msgs::Odometry &msg, double v_x, double
00068 v_theta);
00069
00070 ros::NodeHandle n_;
00071 double sigma_x_, sigma_theta_, cov_x_y_, cov_x_theta_, cov_y_theta_;
00072 bool publish_tf_;
00073 std::string tf_prefix_;
00074
00075 tf::TransformBroadcaster odom_broadcaster_;
00076 ros::Publisher odom_pub_;
00077 ros::Publisher joint_pub_;
00078 };
00079
00080 void ROSComm::setTFPrefix(const std::string &tf_prefix)
00081 {
00082 tf_prefix_ = tf_prefix;
00083 }
00084
00085 void ROSComm::populateCovariance(nav_msgs::Odometry &msg, double v_x, double v_theta)
00086 {
00087 double odom_multiplier = 1.0;
00088
00089 if (fabs(v_x) <= 1e-8 && fabs(v_theta) <= 1e-8)
00090 {
00091
00092 msg.twist.covariance[0] = 1e-12;
00093 msg.twist.covariance[35] = 1e-12;
00094
00095 msg.twist.covariance[30] = 1e-12;
00096 msg.twist.covariance[5] = 1e-12;
00097 }
00098 else
00099 {
00100
00101 msg.twist.covariance[0] = odom_multiplier * pow(sigma_x_, 2);
00102 msg.twist.covariance[35] = odom_multiplier * pow(sigma_theta_, 2);
00103
00104 msg.twist.covariance[30] = odom_multiplier * cov_x_theta_;
00105 msg.twist.covariance[5] = odom_multiplier * cov_x_theta_;
00106 }
00107
00108 msg.twist.covariance[7] = DBL_MAX;
00109 msg.twist.covariance[14] = DBL_MAX;
00110 msg.twist.covariance[21] = DBL_MAX;
00111 msg.twist.covariance[28] = DBL_MAX;
00112
00113 msg.pose.covariance = msg.twist.covariance;
00114
00115 if (fabs(v_x) <= 1e-8 && fabs(v_theta) <= 1e-8)
00116 {
00117 msg.pose.covariance[7] = 1e-12;
00118
00119 msg.pose.covariance[1] = 1e-12;
00120 msg.pose.covariance[6] = 1e-12;
00121
00122 msg.pose.covariance[31] = 1e-12;
00123 msg.pose.covariance[11] = 1e-12;
00124 }
00125 else
00126 {
00127 msg.pose.covariance[7] = odom_multiplier * pow(sigma_x_, 2) * pow(sigma_theta_, 2);
00128
00129 msg.pose.covariance[1] = odom_multiplier * cov_x_y_;
00130 msg.pose.covariance[6] = odom_multiplier * cov_x_y_;
00131
00132 msg.pose.covariance[31] = odom_multiplier * cov_y_theta_;
00133 msg.pose.covariance[11] = odom_multiplier * cov_y_theta_;
00134 }
00135 }
00136
00137 void ROSComm::send_odometry(double x, double y, double theta, double v_x, double v_theta, double wheelpos_l, double wheelpos_r)
00138 {
00139 nav_msgs::Odometry odom;
00140 odom.header.frame_id = tf::resolve(tf_prefix_, "odom_combined");
00141 odom.child_frame_id = tf::resolve(tf_prefix_, "base_footprint");
00142
00143 odom.header.stamp = ros::Time::now();
00144 odom.pose.pose.position.x = x;
00145 odom.pose.pose.position.y = y;
00146 odom.pose.pose.position.z = 0.0;
00147 odom.pose.pose.orientation = tf::createQuaternionMsgFromYaw(theta);
00148
00149 odom.twist.twist.linear.x = v_x;
00150 odom.twist.twist.linear.y = 0.0;
00151 odom.twist.twist.angular.z = v_theta;
00152 populateCovariance(odom, v_x, v_theta);
00153
00154 odom_pub_.publish(odom);
00155
00156 if (publish_tf_)
00157 {
00158 geometry_msgs::TransformStamped odom_trans;
00159 odom_trans.header.frame_id = tf::resolve(tf_prefix_, "odom_combined");
00160 odom_trans.child_frame_id = tf::resolve(tf_prefix_, "base_footprint");
00161
00162 odom_trans.header.stamp = ros::Time::now();
00163 odom_trans.transform.translation.x = x;
00164 odom_trans.transform.translation.y = y;
00165 odom_trans.transform.translation.z = 0.0;
00166 odom_trans.transform.rotation = tf::createQuaternionMsgFromYaw(theta);
00167
00168 odom_broadcaster_.sendTransform(odom_trans);
00169 }
00170
00171 sensor_msgs::JointState joint_state;
00172 joint_state.header.stamp = ros::Time::now();
00173 joint_state.name.resize(6);
00174 joint_state.position.resize(6);
00175 joint_state.name[0] = "left_front_wheel_joint";
00176 joint_state.name[1] = "left_middle_wheel_joint";
00177 joint_state.name[2] = "left_rear_wheel_joint";
00178 joint_state.name[3] = "right_front_wheel_joint";
00179 joint_state.name[4] = "right_middle_wheel_joint";
00180 joint_state.name[5] = "right_rear_wheel_joint";
00181
00182 joint_state.position[0] = joint_state.position[1] = joint_state.position[2] = wheelpos_l;
00183 joint_state.position[3] = joint_state.position[4] = joint_state.position[5] = wheelpos_r;
00184
00185 joint_pub_.publish(joint_state);
00186 }
00187
00188 class ROSCall
00189 {
00190 public:
00191 ROSCall(Volksbot &volksbot, double axis_length) :
00192 volksbot_(volksbot),
00193 axis_length_(axis_length),
00194 last_cmd_vel_time_(0.0) { }
00195 void velCallback(const geometry_msgs::Twist::ConstPtr& msg);
00196 void cmd_velWatchdog(const ros::TimerEvent& event);
00197
00198 private:
00199 Volksbot &volksbot_;
00200 double axis_length_;
00201 ros::Time last_cmd_vel_time_;
00202 };
00203
00204 void ROSCall::velCallback(const geometry_msgs::Twist::ConstPtr& msg)
00205 {
00206 last_cmd_vel_time_ = ros::Time::now();
00207 double max_vel = volksbot_.get_max_vel();
00208 double velocity = msg->linear.x;
00209
00210 velocity = std::min(max_vel, msg->linear.x);
00211 velocity = std::max(-max_vel, msg->linear.x);
00212 volksbot_.set_wheel_speed(velocity - axis_length_ * msg->angular.z * 0.5, velocity + axis_length_ * msg->angular.z * 0.5);
00213 }
00214
00215 void ROSCall::cmd_velWatchdog(const ros::TimerEvent& event)
00216 {
00217 if (ros::Time::now() - last_cmd_vel_time_ > ros::Duration(0.6))
00218 volksbot_.set_wheel_speed(0.0, 0.0);
00219 }
00220
00221 int main(int argc, char** argv)
00222 {
00223 ros::init(argc, argv, "volksbot");
00224 ros::NodeHandle n;
00225 ros::NodeHandle nh_ns("~");
00226
00227
00228
00229 double wheel_radius;
00230 nh_ns.param("wheel_radius", wheel_radius, 0.0985);
00231 double axis_length;
00232 nh_ns.param("axis_length", axis_length, 0.41);
00233 int gear_ratio;
00234 nh_ns.param("gear_ratio", gear_ratio, 74);
00235 int max_vel_l;
00236 nh_ns.param("max_vel_l", max_vel_l, 8250);
00237 int max_vel_r;
00238 nh_ns.param("max_vel_r", max_vel_r, 8400);
00239 int max_acc_l;
00240 nh_ns.param("max_acc_l", max_acc_l, 10000);
00241 int max_acc_r;
00242 nh_ns.param("max_acc_r", max_acc_r, 10000);
00243 bool drive_backwards;
00244 nh_ns.param("drive_backwards", drive_backwards, false);
00245
00246 double turning_adaptation;
00247 nh_ns.param("turning_adaptation", turning_adaptation, 0.95);
00248
00249 double sigma_x, sigma_theta, cov_x_y, cov_x_theta, cov_y_theta;
00250 nh_ns.param("x_stddev", sigma_x, 0.002);
00251 nh_ns.param("rotation_stddev", sigma_theta, 0.017);
00252 nh_ns.param("cov_xy", cov_x_y, 0.0);
00253 nh_ns.param("cov_xrotation", cov_x_theta, 0.0);
00254 nh_ns.param("cov_yrotation", cov_y_theta, 0.0);
00255
00256 ROSComm roscomm(n, sigma_x, sigma_theta, cov_x_y, cov_x_theta, cov_y_theta);
00257
00258 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);
00259
00260 bool publish_tf;
00261 nh_ns.param("publish_tf", publish_tf, false);
00262 std::string tf_prefix;
00263 tf_prefix = tf::getPrefixParam(nh_ns);
00264 roscomm.setTFPrefix(tf_prefix);
00265
00266 ROSCall roscall(volksbot, axis_length);
00267
00268 ros::Timer timer = n.createTimer(ros::Duration(0.1), &ROSCall::cmd_velWatchdog, &roscall);
00269 ros::Subscriber cmd_vel_sub = n.subscribe("cmd_vel", 10, &ROSCall::velCallback, &roscall);
00270
00271 while (ros::ok())
00272 {
00273 volksbot.odometry();
00274 ros::spinOnce();
00275 }
00276
00277 return 0;
00278 }