diff --git a/src/turtlebot_controller/CMakeLists.txt b/src/turtlebot_controller/CMakeLists.txt index ab72574..401031b 100644 --- a/src/turtlebot_controller/CMakeLists.txt +++ b/src/turtlebot_controller/CMakeLists.txt @@ -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 ) diff --git a/src/turtlebot_controller/include/turtlebot_controller/simple_controller.h b/src/turtlebot_controller/include/turtlebot_controller/simple_controller.h index c64096a..13b37f8 100644 --- a/src/turtlebot_controller/include/turtlebot_controller/simple_controller.h +++ b/src/turtlebot_controller/include/turtlebot_controller/simple_controller.h @@ -1,18 +1,44 @@ #ifndef SIMPLE_CONTROLLER_H #define SIMPLE_CONTROLLER_H + #include #include #include +#include +#include +#include + + 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 \ No newline at end of file +#endif \ No newline at end of file diff --git a/src/turtlebot_controller/nodes/simple_controller_node.cpp b/src/turtlebot_controller/nodes/simple_controller_node.cpp index b5aa864..22c845c 100644 --- a/src/turtlebot_controller/nodes/simple_controller_node.cpp +++ b/src/turtlebot_controller/nodes/simple_controller_node.cpp @@ -1,15 +1,17 @@ #include #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; } \ No newline at end of file diff --git a/src/turtlebot_controller/package.xml b/src/turtlebot_controller/package.xml index 7eb9ea1..5150af7 100644 --- a/src/turtlebot_controller/package.xml +++ b/src/turtlebot_controller/package.xml @@ -54,14 +54,26 @@ std_msgs geometry_msgs eigen + sensor_msgs + nav_msgs + tf2 + tf2_ros roscpp rospy eigen + sensor_msgs + nav_msgs + tf2 + tf2_ros roscpp rospy std_msgs geometry_msgs eigen + sensor_msgs + nav_msgs + tf2 + tf2_ros diff --git a/src/turtlebot_controller/src/simple_controller.cpp b/src/turtlebot_controller/src/simple_controller.cpp index 74eefce..7066c28 100644 --- a/src/turtlebot_controller/src/simple_controller.cpp +++ b/src/turtlebot_controller/src/simple_controller.cpp @@ -1,29 +1,116 @@ -#include +#include "turtlebot_controller/simple_controller.h" #include #include +#include +#include -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("wheel_right_controller/command", 10); left_cmd_pub_ = nh_.advertise("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("kubot_description/odom", 10); - vel_sub_ = nh_.subscribe("turtlebot_controller/cmd.vel", 1000, &SimpleController::velCallBack, this); - speed_conversion_ <