]> defiant.homedns.org Git - ros_roboint.git/blob - include/robo_explorer_hardware.h
5c144d502b6953c6a09c368c9b696e3e159d201f
[ros_roboint.git] / include / robo_explorer_hardware.h
1 #include <hardware_interface/joint_command_interface.h>
2 #include <hardware_interface/joint_state_interface.h>
3 #include <hardware_interface/robot_hw.h>
4 #include "roboint/Inputs.h"
5 #include "roboint/Motor.h"
6
7 class RoboExplorer : public hardware_interface::RobotHW
8 {
9         public:
10                 RoboExplorer(ros::NodeHandle nh) { 
11                         this->nh = nh;
12                         pub_motor = nh.advertise<roboint::Motor>("ft/set_motor", 10);
13                         sub_inputs = nh.subscribe("ft/get_inputs", 10, &RoboExplorer::cbInputs, this);
14
15                         // connect and register the joint state interface
16                         hardware_interface::JointStateHandle state_handle_left("left_wheel_joint", &pos[0], &vel[0], &eff[0]);
17                         jnt_state_interface.registerHandle(state_handle_left);
18                         hardware_interface::JointStateHandle state_handle_right("right_wheel_joint", &pos[1], &vel[1], &eff[1]);
19                         jnt_state_interface.registerHandle(state_handle_right);
20                         registerInterface(&jnt_state_interface);
21
22                         // connect and register the joint velocity interface
23                         hardware_interface::JointHandle joint_handle_left(state_handle_left, &cmd[0]);
24                         jnt_velocity_interface.registerHandle(joint_handle_left);
25                         hardware_interface::JointHandle joint_handle_right(state_handle_right, &cmd[1]);
26                         jnt_velocity_interface.registerHandle(joint_handle_right);
27                         registerInterface(&jnt_velocity_interface);
28                 }
29
30                 // Converts pos_encoder from wheels to wheel angles
31                 void read(ros::Duration period) {
32                         static double pos_last[2];
33
34                         pos[0] = pos_encoder[0] * M_PI/8;
35                         pos[1] = pos_encoder[1] * M_PI/8;
36                         vel[0] = (pos[0] - pos_last[0])/period.toSec();
37                         vel[1] = (pos[1] - pos_last[1])/period.toSec();
38                         
39                         std::copy(std::begin(pos), std::end(pos), std::begin(pos_last));
40                 }
41
42                 // Writes current velocity command to hardware
43                 void write() {
44                         double speed_l = 0;
45                         double speed_r = 0;
46                         double wish_speed_left = cmd[0];
47                         double wish_speed_right = cmd[1];
48                         roboint::Motor msg;
49
50                         if (fabs(wish_speed_left) > 0) {
51                                 speed_l = 64.3*fabs(wish_speed_left) -1.7;
52                                 if (wish_speed_left < 0) speed_l*=-1;
53                         }
54                         if (fabs(wish_speed_right) > 0) {
55                                 speed_r = 64.3*fabs(wish_speed_right) -1.7;
56                                 if (wish_speed_right < 0) speed_r*=-1;
57                         }
58
59                         // check limits
60                         if (speed_l < -7) speed_l = -7;
61                         else if (speed_l > 7) speed_l = 7;
62                         if (speed_r < -7) speed_r = -7;
63                         else if (speed_r > 7) speed_r = 7;
64
65                         msg.num = 0;
66                         msg.speed = round(speed_l);
67                         pub_motor.publish(msg);
68
69                         msg.num = 1;
70                         msg.speed = round(speed_r);
71                         pub_motor.publish(msg);
72                 }
73
74                 // Reads current input state and increases pos_encoder on change
75                 void cbInputs(const roboint::Inputs::ConstPtr& msg) {
76                         static std::array<uint8_t, 8> input_last;
77
78                         if (msg->input[0] != input_last[0]) { // left input changed
79                                 // outputs have direction information
80                                 if (msg->output[0] > 0) pos_encoder[0]++;
81                                 else if (msg->output[1] > 0) pos_encoder[0]--;
82                         }
83                         if (msg->input[1] != input_last[1]) { // right input changed
84                                 // outputs have direction information
85                                 if (msg->output[2] > 0) pos_encoder[1]++;
86                                 else if (msg->output[3] > 0) pos_encoder[1]--;
87                         }
88
89                         std::copy(std::begin(msg->input), std::end(msg->input), std::begin(input_last));
90                 }
91
92         private:
93                 hardware_interface::JointStateInterface jnt_state_interface;
94                 hardware_interface::VelocityJointInterface jnt_velocity_interface;
95                 ros::NodeHandle nh;
96                 ros::Publisher pub_motor;
97                 ros::Subscriber sub_inputs;
98                 double cmd[2];
99                 double pos[2];
100                 double vel[2];
101                 double eff[2];
102                 int64_t pos_encoder[2] = {0, 0};
103 };