30 #include <geometry_msgs/Twist.h> 31 #include <nav_msgs/Odometry.h> 34 #include <sensor_msgs/JointState.h> 59 odom_pub_(
n_.advertise<nav_msgs::Odometry> (
"odom", 10)),
61 virtual void send_odometry(
double x,
double y,
double theta,
double v_x,
62 double v_theta,
double wheelpos_l,
double wheelpos_r);
87 double odom_multiplier = 1.0;
89 if (fabs(v_x) <= 1e-8 && fabs(v_theta) <= 1e-8)
92 msg.twist.covariance[0] = 1e-12;
93 msg.twist.covariance[35] = 1e-12;
95 msg.twist.covariance[30] = 1e-12;
96 msg.twist.covariance[5] = 1e-12;
101 msg.twist.covariance[0] = odom_multiplier * pow(
sigma_x_, 2);
102 msg.twist.covariance[35] = odom_multiplier * pow(
sigma_theta_, 2);
104 msg.twist.covariance[30] = odom_multiplier *
cov_x_theta_;
105 msg.twist.covariance[5] = odom_multiplier *
cov_x_theta_;
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;
113 msg.pose.covariance = msg.twist.covariance;
115 if (fabs(v_x) <= 1e-8 && fabs(v_theta) <= 1e-8)
117 msg.pose.covariance[7] = 1e-12;
119 msg.pose.covariance[1] = 1e-12;
120 msg.pose.covariance[6] = 1e-12;
122 msg.pose.covariance[31] = 1e-12;
123 msg.pose.covariance[11] = 1e-12;
129 msg.pose.covariance[1] = odom_multiplier *
cov_x_y_;
130 msg.pose.covariance[6] = odom_multiplier *
cov_x_y_;
132 msg.pose.covariance[31] = odom_multiplier *
cov_y_theta_;
133 msg.pose.covariance[11] = odom_multiplier *
cov_y_theta_;
137 void ROSComm::send_odometry(
double x,
double y,
double theta,
double v_x,
double v_theta,
double wheelpos_l,
double wheelpos_r)
139 nav_msgs::Odometry odom;
144 odom.pose.pose.position.x = x;
145 odom.pose.pose.position.y = y;
146 odom.pose.pose.position.z = 0.0;
149 odom.twist.twist.linear.x = v_x;
150 odom.twist.twist.linear.y = 0.0;
151 odom.twist.twist.angular.z = v_theta;
158 geometry_msgs::TransformStamped odom_trans;
163 odom_trans.transform.translation.x = x;
164 odom_trans.transform.translation.y = y;
165 odom_trans.transform.translation.z = 0.0;
171 sensor_msgs::JointState joint_state;
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";
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;
193 axis_length_(axis_length),
194 last_cmd_vel_time_(0.0) { }
195 void velCallback(
const geometry_msgs::Twist::ConstPtr& msg);
207 double max_vel = volksbot_.get_max_vel();
208 double velocity = msg->linear.x;
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);
218 volksbot_.set_wheel_speed(0.0, 0.0);
221 int main(
int argc,
char** argv)
230 nh_ns.
param(
"wheel_radius", wheel_radius, 0.0985);
232 nh_ns.
param(
"axis_length", axis_length, 0.41);
234 nh_ns.
param(
"gear_ratio", gear_ratio, 74);
236 nh_ns.
param(
"max_vel_l", max_vel_l, 8250);
238 nh_ns.
param(
"max_vel_r", max_vel_r, 8400);
240 nh_ns.
param(
"max_acc_l", max_acc_l, 10000);
242 nh_ns.
param(
"max_acc_r", max_acc_r, 10000);
243 bool drive_backwards;
244 nh_ns.
param(
"drive_backwards", drive_backwards,
false);
246 double turning_adaptation;
247 nh_ns.
param(
"turning_adaptation", turning_adaptation, 0.95);
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);
256 ROSComm roscomm(n, sigma_x, sigma_theta, cov_x_y, cov_x_theta, cov_y_theta);
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);
261 nh_ns.
param(
"publish_tf", publish_tf,
false);
262 std::string tf_prefix;
266 ROSCall roscall(volksbot, axis_length);
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)
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)
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::string resolve(const std::string &prefix, const std::string &frame_name)
void setTFPrefix(const std::string &tf_prefix)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void cmd_velWatchdog(const ros::TimerEvent &event)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
ros::Time last_cmd_vel_time_
TFSIMD_FORCE_INLINE const tfScalar & x() const
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)
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()