controller.h
Go to the documentation of this file.
1 #include <iostream>
2 #include <ros/ros.h>
3 #include <geometry_msgs/Twist.h>
4 #include <std_msgs/Float64.h>
5 #include <nav_msgs/Odometry.h>
6 
9 #include <geometry_msgs/TransformStamped.h>
10 
11 
13 {
14 public:
15  controller(ros::NodeHandle & nh, ros::NodeHandle& nh_private);
16 
17  void init_vars();
18 
19  void cmd_vel_cb(const geometry_msgs::Twist &vel);
20 
21  void odom_cb(const nav_msgs::Odometry &);
22 
23  void vel_publish();
24 
25  void stop_bot();
26 
27  void get_params();
28 
29 private:
32 
35 
40 
41  geometry_msgs::Twist velocity;
42  // std_msgs::Float64 omega;
43  std_msgs::Float64 omega_1, omega_2, omega_3, omega_4;
44  float x_dot, y_dot;
45  float yaw;
46 
48 
50 };
ros::NodeHandle nh_
Definition: controller.h:30
std_msgs::Float64 omega_2
Definition: controller.h:43
float max_lin_vel
Definition: controller.h:49
float vel_mul
Definition: controller.h:47
void get_params()
Definition: controller.cpp:118
void vel_publish()
Definition: controller.cpp:100
ros::Publisher back_left_cmd_pub
Definition: controller.h:39
ros::Subscriber odom_sub_
Definition: controller.h:34
float y_dot
Definition: controller.h:44
float x_dot
Definition: controller.h:44
std_msgs::Float64 omega_4
Definition: controller.h:43
ros::Subscriber vel_sub
Definition: controller.h:33
std_msgs::Float64 omega_1
Definition: controller.h:43
ros::Publisher back_right_cmd_pub
Definition: controller.h:38
float yaw
Definition: controller.h:45
ros::NodeHandle nh_private_
Definition: controller.h:31
ros::Publisher front_right_cmd_pub
Definition: controller.h:36
geometry_msgs::Twist velocity
Definition: controller.h:41
ros::Publisher front_left_cmd_pub
Definition: controller.h:37
void cmd_vel_cb(const geometry_msgs::Twist &vel)
Definition: controller.cpp:61
void odom_cb(const nav_msgs::Odometry &)
Definition: controller.cpp:42
void stop_bot()
Definition: controller.cpp:108
float diag_dist
Definition: controller.h:47
void init_vars()
Definition: controller.cpp:30
float max_angular_vel
Definition: controller.h:49
float wheel_rad
Definition: controller.h:47
std_msgs::Float64 omega_3
Definition: controller.h:43
controller(ros::NodeHandle &nh, ros::NodeHandle &nh_private)
Definition: controller.cpp:9


omnibase_control
Author(s): Harshal Deshpande , Mihir Kulkarni
autogenerated on Mon Feb 28 2022 23:01:32