adding odometry
This commit is contained in:
parent
7160ce6809
commit
145bf17cb7
|
|
@ -6,6 +6,10 @@ find_package(catkin REQUIRED COMPONENTS
|
|||
rospy
|
||||
std_msgs
|
||||
geometry_msgs
|
||||
sensor_msgs
|
||||
nav_msgs
|
||||
tf2
|
||||
tf2_ros
|
||||
)
|
||||
find_package(Eigen3 REQUIRED)
|
||||
|
||||
|
|
@ -14,6 +18,10 @@ INCLUDE_DIRS include
|
|||
CATKIN_DEPENDS
|
||||
std_msgs
|
||||
geometry_msgs
|
||||
sensor_msgs
|
||||
nav_msgs
|
||||
tf2
|
||||
tf2_ros
|
||||
DEPENDS Eigen3
|
||||
# DEPENDS system_lib
|
||||
)
|
||||
|
|
|
|||
|
|
@ -1,18 +1,44 @@
|
|||
#ifndef SIMPLE_CONTROLLER_H
|
||||
#define SIMPLE_CONTROLLER_H
|
||||
|
||||
#include <ros/ros.h>
|
||||
#include <geometry_msgs/Twist.h>
|
||||
#include <Eigen/Core>
|
||||
#include <sensor_msgs/JointState.h>
|
||||
#include <nav_msgs/Odometry.h>
|
||||
#include <geometry_msgs/TransformStamped.h>
|
||||
|
||||
|
||||
class SimpleController
|
||||
{
|
||||
public:
|
||||
SimpleController(const ros::NodeHandle & ,double radius, double seperation);
|
||||
private:
|
||||
void velCallBack(const geometry_msgs::Twist &);
|
||||
public:
|
||||
SimpleController(const ros::NodeHandle &, double radius, double separation);
|
||||
|
||||
private:
|
||||
void velCallback(const geometry_msgs::Twist &);
|
||||
|
||||
void jointCallback(const sensor_msgs::JointState &);
|
||||
|
||||
ros::NodeHandle nh_;
|
||||
ros::Subscriber vel_sub_;
|
||||
ros::Publisher right_cmd_pub_;
|
||||
ros::Publisher left_cmd_pub_;
|
||||
ros::Subscriber joint_sub_;
|
||||
ros::Publisher odom_pub_;
|
||||
|
||||
// Differential Kinematics
|
||||
Eigen::Matrix2d speed_conversion_;
|
||||
|
||||
// Odometry
|
||||
double wheel_radius_;
|
||||
double wheel_separation_;
|
||||
double right_wheel_prev_pos_;
|
||||
double left_wheel_prev_pos_;
|
||||
ros::Time prev_time_;
|
||||
nav_msgs::Odometry odom_msg_;
|
||||
double x_;
|
||||
double y_;
|
||||
double theta_;
|
||||
geometry_msgs::TransformStamped transform_stamped_;
|
||||
};
|
||||
#endif
|
||||
#endif
|
||||
|
|
@ -1,15 +1,17 @@
|
|||
#include <ros/ros.h>
|
||||
#include "turtlebot_controller/simple_controller.h"
|
||||
|
||||
int main(int argc, char **argv){
|
||||
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
ros::init(argc, argv, "simple_controller");
|
||||
ros::NodeHandle nh;
|
||||
ros::NodeHandle pnh("~");
|
||||
double wheel_radius;
|
||||
double wheel_radius, wheel_separation;
|
||||
pnh.getParam("wheel_radius", wheel_radius);
|
||||
double wheel_seperation;
|
||||
pnh.getParam("wheel_seperation", wheel_seperation);
|
||||
SimpleController controller(nh, wheel_radius, wheel_seperation);
|
||||
pnh.getParam("wheel_separation", wheel_separation);
|
||||
SimpleController controller(nh, wheel_radius, wheel_separation);
|
||||
ros::spin();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
|
@ -54,14 +54,26 @@
|
|||
<build_depend>std_msgs</build_depend>
|
||||
<build_depend>geometry_msgs</build_depend>
|
||||
<build_depend>eigen</build_depend>
|
||||
<build_depend>sensor_msgs</build_depend>
|
||||
<build_depend>nav_msgs</build_depend>
|
||||
<build_depend>tf2</build_depend>
|
||||
<build_depend>tf2_ros</build_depend>
|
||||
<build_export_depend>roscpp</build_export_depend>
|
||||
<build_export_depend>rospy</build_export_depend>
|
||||
<build_export_depend>eigen</build_export_depend>
|
||||
<build_export_depend>sensor_msgs</build_export_depend>
|
||||
<build_export_depend>nav_msgs</build_export_depend>
|
||||
<build_export_depend>tf2</build_export_depend>
|
||||
<build_export_depend>tf2_ros</build_export_depend>
|
||||
<exec_depend>roscpp</exec_depend>
|
||||
<exec_depend>rospy</exec_depend>
|
||||
<exec_depend>std_msgs</exec_depend>
|
||||
<exec_depend>geometry_msgs</exec_depend>
|
||||
<exec_depend>eigen</exec_depend>
|
||||
<exec_depend>sensor_msgs</exec_depend>
|
||||
<exec_depend>nav_msgs</exec_depend>
|
||||
<exec_depend>tf2</exec_depend>
|
||||
<exec_depend>tf2_ros</exec_depend>
|
||||
|
||||
<!-- The export tag contains other, unspecified, tags -->
|
||||
<export>
|
||||
|
|
|
|||
|
|
@ -1,29 +1,116 @@
|
|||
#include <turtlebot_controller/simple_controller.h>
|
||||
#include "turtlebot_controller/simple_controller.h"
|
||||
#include <std_msgs/Float64.h>
|
||||
#include <Eigen/Geometry>
|
||||
#include <tf2/LinearMath/Quaternion.h>
|
||||
#include <tf2_ros/transform_broadcaster.h>
|
||||
|
||||
SimpleController::SimpleController(const ros::NodeHandle &nh ,double radius, double seperation): nh_(nh)
|
||||
|
||||
SimpleController::SimpleController(const ros::NodeHandle &nh,
|
||||
double radius,
|
||||
double separation)
|
||||
: nh_(nh)
|
||||
, wheel_radius_(radius)
|
||||
, wheel_separation_(separation)
|
||||
, left_wheel_prev_pos_(0.0)
|
||||
, right_wheel_prev_pos_(0.0)
|
||||
, x_(0.0)
|
||||
, y_(0.0)
|
||||
, theta_(0.0)
|
||||
{
|
||||
ROS_INFO_STREAM("Using wheel raduis" << radius);
|
||||
ROS_INFO_STREAM("Using wheel seperation" << seperation);
|
||||
ROS_INFO_STREAM("Using wheel radius " << radius);
|
||||
ROS_INFO_STREAM("Using wheel separation " << separation);
|
||||
right_cmd_pub_ = nh_.advertise<std_msgs::Float64>("wheel_right_controller/command", 10);
|
||||
left_cmd_pub_ = nh_.advertise<std_msgs::Float64>("wheel_left_controller/command", 10);
|
||||
vel_sub_ = nh_.subscribe("kubot_description/cmd_vel", 1000, &SimpleController::velCallback, this);
|
||||
joint_sub_ = nh_.subscribe("joint_states", 1000, &SimpleController::jointCallback, this);
|
||||
odom_pub_ = nh_.advertise<nav_msgs::Odometry>("kubot_description/odom", 10);
|
||||
|
||||
vel_sub_ = nh_.subscribe("turtlebot_controller/cmd.vel", 1000, &SimpleController::velCallBack, this);
|
||||
speed_conversion_ <<radius/2, radius/2, radius/seperation, -radius/seperation;
|
||||
speed_conversion_ << radius/2, radius/2, radius/separation, -radius/separation;
|
||||
ROS_INFO_STREAM("The conversion matrix is \n" << speed_conversion_);
|
||||
|
||||
// Fill the Odometry message with invariant parameters
|
||||
odom_msg_.header.frame_id = "odom";
|
||||
odom_msg_.child_frame_id = "base_footprint";
|
||||
odom_msg_.pose.pose.orientation.x = 0.0;
|
||||
odom_msg_.pose.pose.orientation.y = 0.0;
|
||||
odom_msg_.pose.pose.orientation.z = 0.0;
|
||||
odom_msg_.pose.pose.orientation.w = 1.0;
|
||||
|
||||
transform_stamped_.header.frame_id = "odom";
|
||||
transform_stamped_.child_frame_id = "base_footprint";
|
||||
|
||||
prev_time_ = ros::Time::now();
|
||||
}
|
||||
void SimpleController::velCallBack(const geometry_msgs::Twist &msg)
|
||||
|
||||
|
||||
void SimpleController::velCallback(const geometry_msgs::Twist &msg)
|
||||
{
|
||||
// Implements the differential kinematic model
|
||||
// Given v and w, calculate the velocities of the wheels
|
||||
Eigen::Vector2d robot_speed(msg.linear.x, msg.angular.z);
|
||||
Eigen::Vector2d wheel_speed = speed_conversion_.inverse() * robot_speed;
|
||||
|
||||
std_msgs::Float64 right_speed;
|
||||
right_speed.data = wheel_speed.coeff(0);
|
||||
std_msgs::Float64 left_speed;
|
||||
right_speed.data =wheel_speed.coeff(0);
|
||||
left_speed.data = wheel_speed.coeff(1);
|
||||
|
||||
right_cmd_pub_.publish(right_speed);
|
||||
left_cmd_pub_.publish(left_speed);
|
||||
}
|
||||
|
||||
|
||||
void SimpleController::jointCallback(const sensor_msgs::JointState &state)
|
||||
{
|
||||
// Implements the inverse differential kinematic model
|
||||
// Given the position of the wheels, calculates their velocities
|
||||
// then calculates the velocity of the robot wrt the robot frame
|
||||
// and then converts it in the global frame and publishes the TF
|
||||
double dp_left = state.position.at(0) - left_wheel_prev_pos_;
|
||||
double dp_right = state.position.at(1) - right_wheel_prev_pos_;
|
||||
double dt = (state.header.stamp - prev_time_).toSec();
|
||||
|
||||
// Actualize the prev pose for the next itheration
|
||||
left_wheel_prev_pos_ = state.position.at(0);
|
||||
right_wheel_prev_pos_ = state.position.at(1);
|
||||
prev_time_ = state.header.stamp;
|
||||
|
||||
// Calculate the rotational speed of each wheel
|
||||
double fi_left = dp_left / dt;
|
||||
double fi_right = dp_right / dt;
|
||||
|
||||
// Calculate the linear and angular velocity
|
||||
double linear = (wheel_radius_ * fi_right + wheel_radius_ * fi_left) / 2;
|
||||
double angular = (wheel_radius_ * fi_right - wheel_radius_ * fi_left) / wheel_separation_;
|
||||
|
||||
// Calculate the position increment
|
||||
double d_s = (wheel_radius_ * dp_right + wheel_radius_ * dp_left) / 2;
|
||||
double d_theta = (wheel_radius_ * dp_right - wheel_radius_ * dp_left) / wheel_separation_;
|
||||
theta_ += d_theta;
|
||||
x_ += d_s * cos(theta_);
|
||||
y_ += d_s * sin(theta_);
|
||||
|
||||
// Compose and publish the odom message
|
||||
tf2::Quaternion q;
|
||||
q.setRPY(0, 0, theta_);
|
||||
odom_msg_.header.stamp = ros::Time::now();
|
||||
odom_msg_.pose.pose.position.x = x_;
|
||||
odom_msg_.pose.pose.position.y = y_;
|
||||
odom_msg_.pose.pose.orientation.x = q.getX();
|
||||
odom_msg_.pose.pose.orientation.y = q.getY();
|
||||
odom_msg_.pose.pose.orientation.z = q.getZ();
|
||||
odom_msg_.pose.pose.orientation.w = q.getW();
|
||||
odom_msg_.twist.twist.linear.x = linear;
|
||||
odom_msg_.twist.twist.angular.z = angular;
|
||||
odom_pub_.publish(odom_msg_);
|
||||
|
||||
// TF
|
||||
static tf2_ros::TransformBroadcaster br;
|
||||
transform_stamped_.transform.translation.x = x_;
|
||||
transform_stamped_.transform.translation.y = y_;
|
||||
transform_stamped_.transform.rotation.x = q.getX();
|
||||
transform_stamped_.transform.rotation.y = q.getY();
|
||||
transform_stamped_.transform.rotation.z = q.getZ();
|
||||
transform_stamped_.transform.rotation.w = q.getW();
|
||||
transform_stamped_.header.stamp = ros::Time::now();
|
||||
br.sendTransform(transform_stamped_);
|
||||
}
|
||||
Loading…
Reference in New Issue