Skip to content

Commit 4c65385

Browse files
authored
Merge pull request #168 from BCLab-UNM/sbridge-comments
Sbridge comments
2 parents 479d4ce + 5c8f085 commit 4c65385

File tree

2 files changed

+68
-9
lines changed

2 files changed

+68
-9
lines changed

src/sbridge/src/sbridge.cpp

Lines changed: 64 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,72 +1,131 @@
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
15
#include "sbridge.h"
26

7+
// sbridge constructor
38
sbridge::sbridge(std::string publishedName) {
49

10+
// Create a new node that will communicate with ROS
511
ros::NodeHandle sNH;
612

713

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
819
driveControlSubscriber = sNH.subscribe((publishedName + "/driveControl"), 10, &sbridge::cmdHandler, this);
920

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
1027
heartbeatPublisher = sNH.advertise<std_msgs::String>((publishedName + "/sbridge/heartbeat"), 1, false);
28+
29+
// Create a skidsteer publisher to
1130
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
1233
infoLogPublisher = sNH.advertise<std_msgs::String>("/infoLog", 1, true);
1334

35+
// Publishes a heartbeat every 2 seconds
1436
float heartbeat_publish_interval = 2;
15-
publish_heartbeat_timer = sNH.createTimer(ros::Duration(heartbeat_publish_interval), &sbridge::publishHeartBeatTimerEventHandler, this);
1637

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);
1744

18-
ROS_INFO("constructor");
45+
ROS_INFO("constructor");
1946

2047
}
2148

49+
// Command Handler
50+
// PWM (pulse with modulation) values to linear values
2251
void sbridge::cmdHandler(const geometry_msgs::Twist::ConstPtr& message) {
52+
// Gets and sets the linear PWM value
2353
double left = (message->linear.x);
54+
// Gets and sets the angular PWM value
2455
double right = (message->angular.z);
2556

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
2860

61+
// Temperary Variables to store the velocity values
62+
// Angular
2963
float turn = 0;
64+
// Linear
3065
float forward = 0;
3166

3267
float linearVel = (left + right)/2;
3368
float angularVel = (right-left)/2;
3469

70+
// Converts the PWM values to velocity values
71+
// Necessary hand-tuned conversion value
3572
turn = angularVel/55;
73+
// Necessary hand-tuned conversion value
3674
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
3779
if (forward >= 150){
80+
// Lower forward velocity value by necessary hand-tuned conversion value
3881
forward -= (abs(turn)/5);
3982
}
4083

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)
4186
if (linearVel >= 0 && forward <= 0)
4287
{
88+
// Do not move (set forward velocity to 0)
4389
forward = 0;
4490
}
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)
4594
if (linearVel <= 0 && forward >= 0)
4695
{
96+
// Do not move (set forward velocity to 0)
4797
forward = 0;
4898
}
4999

100+
// If the absolute value of the forward value (float) is greater than or equal to the max_linear_velocity
50101
if (fabs(forward) >= max_linear_velocity) {
51102
forward = forward/fabs(forward) * max_linear_velocity;
52103
}
53104

54-
if (fabs(turn) >= max_turn_rate) { //max value needs tuning
105+
if (fabs(turn) >= max_turn_rate) { // max value needs tuning
55106
turn = turn/fabs(turn) * max_turn_rate;
56107
}
57108

109+
// Sets the converted (PWM to velocity) values into the variable that the simulation can read
110+
// Linear velocity
58111
velocity.linear.x = forward,
112+
// Angular velocity
59113
velocity.angular.z = turn;
114+
// Publish velocity information to rotary wheel movement
60115
skidsteerPublish.publish(velocity);
61116
}
62117

118+
63119
void sbridge::publishHeartBeatTimerEventHandler(const ros::TimerEvent& event) {
64120
std_msgs::String msg;
65121
msg.data = "";
122+
// Publish the heartbeat message
66123
heartbeatPublisher.publish(msg);
67124

125+
// Log information for the timer in seconds and nanoseconds
68126
ROS_INFO("%ds, %dnsec", event.last_real.sec, event.last_real.nsec);
69127
}
70128

129+
// Destructor
71130
sbridge::~sbridge() {
72131
}

src/sbridge/src/sbridge.h

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
#ifndef SBRIDGE
22
#define SBRIDGE
33

4-
//ROS messages
4+
// ROS messages
55
#include <ros/ros.h>
66
#include <std_msgs/Float32.h>
77
#include <std_msgs/String.h>
@@ -26,16 +26,16 @@ class sbridge {
2626

2727
private:
2828

29-
//Publishers
29+
// Publishers
3030
ros::Publisher skidsteerPublish;
3131
ros::Publisher heartbeatPublisher;
3232
ros::Publisher infoLogPublisher;
3333

34-
//Subscribers
34+
// Subscribers
3535
ros::Subscriber driveControlSubscriber;
3636
ros::Subscriber modeSubscriber;
3737

38-
//Timer callback handler
38+
// Timer callback handler
3939
void publishHeartBeatTimerEventHandler(const ros::TimerEvent& event);
4040

4141
ros::Timer publish_heartbeat_timer;

0 commit comments

Comments
 (0)