30 #include <geometry_msgs/Twist.h> 31 #include <nav_msgs/Odometry.h> 34 #include <sensor_msgs/JointState.h> 53 std::vector<std::string> joint_names) :
61 odom_pub_(
n_.advertise<nav_msgs::Odometry> (
"odom", 10)),
66 virtual void send_odometry(
double x,
double y,
double theta,
double v_x,
67 double v_theta,
double wheelpos_l,
double wheelpos_r);
94 double odom_multiplier = 1.0;
96 if (fabs(v_x) <= 1e-8 && fabs(v_theta) <= 1e-8)
99 msg.twist.covariance[0] = 1e-12;
100 msg.twist.covariance[35] = 1e-12;
102 msg.twist.covariance[30] = 1e-12;
103 msg.twist.covariance[5] = 1e-12;
108 msg.twist.covariance[0] = odom_multiplier * pow(
sigma_x_, 2);
109 msg.twist.covariance[35] = odom_multiplier * pow(
sigma_theta_, 2);
111 msg.twist.covariance[30] = odom_multiplier *
cov_x_theta_;
112 msg.twist.covariance[5] = odom_multiplier *
cov_x_theta_;
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;
120 msg.pose.covariance = msg.twist.covariance;
122 if (fabs(v_x) <= 1e-8 && fabs(v_theta) <= 1e-8)
124 msg.pose.covariance[7] = 1e-12;
126 msg.pose.covariance[1] = 1e-12;
127 msg.pose.covariance[6] = 1e-12;
129 msg.pose.covariance[31] = 1e-12;
130 msg.pose.covariance[11] = 1e-12;
136 msg.pose.covariance[1] = odom_multiplier *
cov_x_y_;
137 msg.pose.covariance[6] = odom_multiplier *
cov_x_y_;
139 msg.pose.covariance[31] = odom_multiplier *
cov_y_theta_;
140 msg.pose.covariance[11] = odom_multiplier *
cov_y_theta_;
144 void ROSComm::send_odometry(
double x,
double y,
double theta,
double v_x,
double v_theta,
double wheelpos_l,
double wheelpos_r)
146 nav_msgs::Odometry odom;
151 odom.pose.pose.position.x = x;
152 odom.pose.pose.position.y = y;
153 odom.pose.pose.position.z = 0.0;
156 odom.twist.twist.linear.x = v_x;
157 odom.twist.twist.linear.y = 0.0;
158 odom.twist.twist.angular.z = v_theta;
165 geometry_msgs::TransformStamped odom_trans;
170 odom_trans.transform.translation.x = x;
171 odom_trans.transform.translation.y = y;
172 odom_trans.transform.translation.z = 0.0;
178 sensor_msgs::JointState joint_state;
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;
191 joint_state.position[0] = joint_state.position[1] = wheelpos_l;
192 joint_state.position[2] = joint_state.position[3] = wheelpos_r;
203 axis_length_(axis_length),
204 last_cmd_vel_time_(0.0) { }
205 void velCallback(
const geometry_msgs::Twist::ConstPtr& msg);
217 double max_vel = volksbot_.get_max_vel();
218 double velocity = msg->linear.x;
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);
228 volksbot_.set_wheel_speed(0.0, 0.0);
231 int main(
int argc,
char** argv)
240 nh_ns.
param(
"wheel_radius", wheel_radius, 0.0985);
242 nh_ns.
param(
"axis_length", axis_length, 0.41);
244 nh_ns.
param(
"gear_ratio", gear_ratio, 74);
246 nh_ns.
param(
"max_vel_l", max_vel_l, 8250);
248 nh_ns.
param(
"max_vel_r", max_vel_r, 8400);
250 nh_ns.
param(
"max_acc_l", max_acc_l, 10000);
252 nh_ns.
param(
"max_acc_r", max_acc_r, 10000);
253 bool drive_backwards;
254 nh_ns.
param(
"drive_backwards", drive_backwards,
false);
256 double turning_adaptation;
257 nh_ns.
param(
"turning_adaptation", turning_adaptation, 0.95);
261 nh_ns.
param(
"num_wheels", num_wheels, 6);
262 if(num_wheels != 4 && num_wheels != 6)
264 ROS_FATAL(
"Wrong configuration of the volksbot driver: Only four or six wheels are supported! See param \"num_wheels\".");
268 std::vector<std::string> joint_names;
269 if(nh_ns.
getParam(
"joint_names", joint_names))
271 if(num_wheels != joint_names.size())
273 ROS_FATAL(
"Wrong configuration of the volksbot driver: The number of joint names must equak the number of wheels!");
276 ROS_INFO(
"Using joint names from \"joint_names\" parameter list");
278 else if(num_wheels == 6)
280 ROS_INFO(
"Using default joint names for six wheels.");
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" 294 ROS_INFO(
"Using default joint names for four wheels.");
296 "left_front_wheel_joint",
297 "left_rear_wheel_joint",
298 "right_front_wheel_joint",
299 "right_rear_wheel_joint" 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);
310 ROSComm roscomm(n, sigma_x, sigma_theta, cov_x_y, cov_x_theta, cov_y_theta, num_wheels, joint_names);
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);
315 nh_ns.
param(
"publish_tf", publish_tf,
false);
316 std::string tf_prefix;
320 ROSCall roscall(volksbot, axis_length);
void velCallback(const geometry_msgs::Twist::ConstPtr &msg)
int main(int argc, char **argv)
std::string getPrefixParam(ros::NodeHandle &nh)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
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::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)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
void setTFPrefix(const std::string &tf_prefix)
bool getParam(const std::string &key, std::string &s) const
void cmd_velWatchdog(const ros::TimerEvent &event)
ros::Time last_cmd_vel_time_
ROSCall(Volksbot &volksbot, double axis_length)
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_
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()