|
| 1 | +// This file handles communication between the gazebo simulation and the rover |
| 2 | + |
| 3 | +// Since the simulation cannot get data from the real rovers, this package converts |
| 4 | +// the behavior package data into readable data for the gazebo simulation to understand |
1 | 5 | #include "sbridge.h" |
2 | 6 |
|
| 7 | +// sbridge constructor |
3 | 8 | sbridge::sbridge(std::string publishedName) { |
4 | 9 |
|
| 10 | + // Create a new node that will communicate with ROS |
5 | 11 | ros::NodeHandle sNH; |
6 | 12 |
|
7 | 13 |
|
| 14 | + // Create a drive control subscriber |
| 15 | + // publishedName + '/driveControl" == the topic to subscribe to |
| 16 | + // 10 == the incoming message queue size |
| 17 | + // &sbridge::cmdHandler == callback to class method first parameter |
| 18 | + // this == calllback to class method second parameter |
8 | 19 | driveControlSubscriber = sNH.subscribe((publishedName + "/driveControl"), 10, &sbridge::cmdHandler, this); |
9 | 20 |
|
| 21 | + // Create a heatbeat publisher to show that the node is still alive and running |
| 22 | + // publishedName + "/sbridge/heartbeat" == topic to publish to |
| 23 | + // 1 == the outgoing message queue |
| 24 | + // false == disables the latching connection. It does not save the last message nor automatically send |
| 25 | + // automatically send it to future connecting subscribers |
| 26 | + // this parameter is optional |
10 | 27 | heartbeatPublisher = sNH.advertise<std_msgs::String>((publishedName + "/sbridge/heartbeat"), 1, false); |
| 28 | + |
| 29 | + // Create a skidsteer publisher to |
11 | 30 | skidsteerPublish = sNH.advertise<geometry_msgs::Twist>((publishedName + "/skidsteer"), 10); |
| 31 | + |
| 32 | + // Create a infoLog publisher to send log information to the log box in the GUI |
12 | 33 | infoLogPublisher = sNH.advertise<std_msgs::String>("/infoLog", 1, true); |
13 | 34 |
|
| 35 | + // Publishes a heartbeat every 2 seconds |
14 | 36 | float heartbeat_publish_interval = 2; |
15 | | - publish_heartbeat_timer = sNH.createTimer(ros::Duration(heartbeat_publish_interval), &sbridge::publishHeartBeatTimerEventHandler, this); |
16 | 37 |
|
| 38 | + // Schedules a callback at the heartbeat_publish_interval |
| 39 | + // This is not a realtime timer |
| 40 | + // ros::Duration(heartbeat_publish_interval) == period between calls to the callback |
| 41 | + // &sbridge::publishHeartBeatTimerEventHandler == callback to class method first parameter |
| 42 | + // this == callback to class method second parameter |
| 43 | + publish_heartbeat_timer = sNH.createTimer(ros::Duration(heartbeat_publish_interval), &sbridge::publishHeartBeatTimerEventHandler, this); |
17 | 44 |
|
18 | | - ROS_INFO("constructor"); |
| 45 | + ROS_INFO("constructor"); |
19 | 46 |
|
20 | 47 | } |
21 | 48 |
|
| 49 | +// Command Handler |
| 50 | +// PWM (pulse with modulation) values to linear values |
22 | 51 | void sbridge::cmdHandler(const geometry_msgs::Twist::ConstPtr& message) { |
| 52 | + // Gets and sets the linear PWM value |
23 | 53 | double left = (message->linear.x); |
| 54 | + // Gets and sets the angular PWM value |
24 | 55 | double right = (message->angular.z); |
25 | 56 |
|
26 | | - float max_turn_rate = 4.5; //radians per second |
27 | | - float max_linear_velocity = 0.65; // meters per second |
| 57 | + // Set max values |
| 58 | + float max_turn_rate = 4.5; // radians per second |
| 59 | + float max_linear_velocity = 0.65; // meters per second |
28 | 60 |
|
| 61 | + // Temperary Variables to store the velocity values |
| 62 | + // Angular |
29 | 63 | float turn = 0; |
| 64 | + // Linear |
30 | 65 | float forward = 0; |
31 | 66 |
|
32 | 67 | float linearVel = (left + right)/2; |
33 | 68 | float angularVel = (right-left)/2; |
34 | 69 |
|
| 70 | + // Converts the PWM values to velocity values |
| 71 | + // Necessary hand-tuned conversion value |
35 | 72 | turn = angularVel/55; |
| 73 | + // Necessary hand-tuned conversion value |
36 | 74 | forward = linearVel/390; |
| 75 | + |
| 76 | + // If the rover is moving forward and turning at the same time, it will not have enough power to carry out |
| 77 | + // each of those at it's full values, so we need to lower this value so the PIDs can compensate for both |
| 78 | + // the linear and angular velocity |
37 | 79 | if (forward >= 150){ |
| 80 | + // Lower forward velocity value by necessary hand-tuned conversion value |
38 | 81 | forward -= (abs(turn)/5); |
39 | 82 | } |
40 | 83 |
|
| 84 | + // If the linear velocity (PWM value) is moving in the forward direction (value is greater than or equal to 0), |
| 85 | + // but forward (velocity) gets converted to a non-positive value (for reverse movement) |
41 | 86 | if (linearVel >= 0 && forward <= 0) |
42 | 87 | { |
| 88 | + // Do not move (set forward velocity to 0) |
43 | 89 | forward = 0; |
44 | 90 | } |
| 91 | + |
| 92 | + // If the linear velocity (PWM value) is moving in the reverse direction (value is greater than or equal to 0), |
| 93 | + // but the foward (velocity) variable gets converted to a non-negative value (for forwards movement) |
45 | 94 | if (linearVel <= 0 && forward >= 0) |
46 | 95 | { |
| 96 | + // Do not move (set forward velocity to 0) |
47 | 97 | forward = 0; |
48 | 98 | } |
49 | 99 |
|
| 100 | + // If the absolute value of the forward value (float) is greater than or equal to the max_linear_velocity |
50 | 101 | if (fabs(forward) >= max_linear_velocity) { |
51 | 102 | forward = forward/fabs(forward) * max_linear_velocity; |
52 | 103 | } |
53 | 104 |
|
54 | | - if (fabs(turn) >= max_turn_rate) { //max value needs tuning |
| 105 | + if (fabs(turn) >= max_turn_rate) { // max value needs tuning |
55 | 106 | turn = turn/fabs(turn) * max_turn_rate; |
56 | 107 | } |
57 | 108 |
|
| 109 | + // Sets the converted (PWM to velocity) values into the variable that the simulation can read |
| 110 | + // Linear velocity |
58 | 111 | velocity.linear.x = forward, |
| 112 | + // Angular velocity |
59 | 113 | velocity.angular.z = turn; |
| 114 | + // Publish velocity information to rotary wheel movement |
60 | 115 | skidsteerPublish.publish(velocity); |
61 | 116 | } |
62 | 117 |
|
| 118 | + |
63 | 119 | void sbridge::publishHeartBeatTimerEventHandler(const ros::TimerEvent& event) { |
64 | 120 | std_msgs::String msg; |
65 | 121 | msg.data = ""; |
| 122 | + // Publish the heartbeat message |
66 | 123 | heartbeatPublisher.publish(msg); |
67 | 124 |
|
| 125 | + // Log information for the timer in seconds and nanoseconds |
68 | 126 | ROS_INFO("%ds, %dnsec", event.last_real.sec, event.last_real.nsec); |
69 | 127 | } |
70 | 128 |
|
| 129 | +// Destructor |
71 | 130 | sbridge::~sbridge() { |
72 | 131 | } |
0 commit comments