Odometry communication
Dependencies: PID QEI chair_BNO055 ros_lib_kinetic3
Dependents: wheelchaircontrolrealtime1
Fork of wheelchaircontrol by
Diff: wheelchair.h
- Revision:
- 24:6c5b4b82f874
- Parent:
- 23:58ec657a44f2
- Child:
- 25:987f3bcd769b
- Child:
- 28:889fc0e5f8c4
--- a/wheelchair.h Sat Oct 27 16:47:50 2018 +0000 +++ b/wheelchair.h Fri Nov 02 02:15:30 2018 +0000 @@ -7,6 +7,7 @@ #include "QEI.h" #include <ros.h> #include <geometry_msgs/Twist.h> +#include <nav_msgs/Odometry.h> /* @@ -64,6 +65,7 @@ /* function to get imu data*/ void compass_thread(); void velosity_thread(); + void rosCom_thread(); /* move x millimiters foward using PID*/ void pid_forward(double mm); @@ -91,6 +93,10 @@ void kitchen(); void desk_to_kitchen(); + double x_position; + double y_position; + double z_angular; + double odom_vector[3]; private: /* Pointers for the joystick speed*/ PwmOut* x;