Skip to content

Commit 32e7f6c

Browse files
committed
Implement PCB communication using flatbuffers
1 parent 2a40817 commit 32e7f6c

31 files changed

+10373
-543
lines changed

noah_behaviour/config/environment.yaml

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,17 +1,17 @@
11
#information about the robot
22

33
# PCB communication
4-
PCB_UART_PORT: "/dev/ttyACM0"
5-
PCB_UART_UPDATE_RATE_HZ: 20
4+
PCB_BRIDGE_UART_PORT: "/dev/ttyS0"
5+
PCB_BRIDGE_CHECK_INTERVAL_MS: 40
6+
MOTOR_MAX_SPEED_METER_SEC: 0.6
7+
MOTOR_MIN_SPEED_METER_SEC: 0.1
68

79
# Physical characteristics of the robot
810
# export TICK_METERS=3653
911
ticks_meter: 3653
1012
BASE_WIDTH: 0.2
1113

1214
# Motor Drive configuration
13-
MAX_SPEED_METER_SEC: 0.5
14-
MIN_SPEED_METER_SEC: 0.1
1515
PID_MIN: 10.0
1616
PID_MAX: 700.0
1717
PID_P: 50.0
Lines changed: 3 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -6,16 +6,11 @@
66
<include file="$(find noah_drivers)/launch/drivers_node.launch"/>
77

88
<node pkg="differential_drive" type="twist_to_motors.py" name="twist_to_motors" output="screen">
9-
<remap from="lwheel_vtarget" to="/motor_left_pwm"/>
10-
<remap from="rwheel_vtarget" to="/motor_right_pwm"/>
9+
<remap from="lwheel_vtarget" to="/motor_left_speed"/>
10+
<remap from="rwheel_vtarget" to="/motor_right_speed"/>
11+
<remap from="twist" to="cmd_vel"/>
1112
<rosparam param="base_width">0.16</rosparam>
1213
<rosparam param="rate">25</rosparam>
1314
</node>
1415

15-
<node pkg="teleop_twist_keyboard" type="teleop_twist_keyboard.py" name="teleop_keyboard" output="screen">
16-
<remap from="cmd_vel" to="/twist"/>
17-
<rosparam param="speed">0.3</rosparam>
18-
<rosparam param="turn">0.8</rosparam>
19-
</node>
20-
2116
</launch>

noah_behaviour/launch/roc.launch

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
<?xml version="1.0"?>
2+
<launch>
3+
<rosparam file="$(find noah_behaviour)/config/environment.yaml" command="load" />
4+
5+
<!-- Spawn rqt_steering -->
6+
<node pkg="rqt_robot_steering" type="rqt_robot_steering" name="steering">
7+
</node>
8+
</launch>

noah_drivers/CMakeLists.txt

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,6 @@ add_compile_options(-std=c++14 -Werror -Wall -Wextra -Wno-unused-parameter -Wno
99
## is used, also find other catkin packages
1010
find_package(catkin REQUIRED COMPONENTS
1111
geometry_msgs
12-
noah_msgs
1312
roscpp
1413
rospy
1514
std_msgs
Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,24 @@
1+
// This file describes all the available data types that can be used
2+
// to communicate with ROS.
3+
4+
namespace noah.ros;
5+
6+
enum Side:byte { All }
7+
8+
struct EncoderRequest {
9+
side:Side;
10+
}
11+
12+
struct EncoderResponse{
13+
ticks_l:int16;
14+
ticks_r:int16;
15+
}
16+
17+
table DataPackage {
18+
encoderRequest:EncoderRequest;
19+
encoderResponse:EncoderResponse;
20+
targetSpeedLRequest:float;
21+
targetSpeedRRequest:float;
22+
}
23+
24+
root_type DataPackage;
Lines changed: 190 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,190 @@
1+
// automatically generated by the FlatBuffers compiler, do not modify
2+
3+
4+
#ifndef FLATBUFFERS_GENERATED_DATAPACKAGE_NOAH_ROS_H_
5+
#define FLATBUFFERS_GENERATED_DATAPACKAGE_NOAH_ROS_H_
6+
7+
#include "flatbuffers/flatbuffers.h"
8+
9+
namespace noah {
10+
namespace ros {
11+
12+
struct EncoderRequest;
13+
14+
struct EncoderResponse;
15+
16+
struct DataPackage;
17+
struct DataPackageBuilder;
18+
19+
enum Side {
20+
Side_All = 0,
21+
Side_MIN = Side_All,
22+
Side_MAX = Side_All
23+
};
24+
25+
inline const Side (&EnumValuesSide())[1] {
26+
static const Side values[] = {
27+
Side_All
28+
};
29+
return values;
30+
}
31+
32+
inline const char * const *EnumNamesSide() {
33+
static const char * const names[2] = {
34+
"All",
35+
nullptr
36+
};
37+
return names;
38+
}
39+
40+
inline const char *EnumNameSide(Side e) {
41+
if (flatbuffers::IsOutRange(e, Side_All, Side_All)) return "";
42+
const size_t index = static_cast<size_t>(e);
43+
return EnumNamesSide()[index];
44+
}
45+
46+
FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(1) EncoderRequest FLATBUFFERS_FINAL_CLASS {
47+
private:
48+
int8_t side_;
49+
50+
public:
51+
EncoderRequest() {
52+
memset(static_cast<void *>(this), 0, sizeof(EncoderRequest));
53+
}
54+
EncoderRequest(noah::ros::Side _side)
55+
: side_(flatbuffers::EndianScalar(static_cast<int8_t>(_side))) {
56+
}
57+
noah::ros::Side side() const {
58+
return static_cast<noah::ros::Side>(flatbuffers::EndianScalar(side_));
59+
}
60+
};
61+
FLATBUFFERS_STRUCT_END(EncoderRequest, 1);
62+
63+
FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(2) EncoderResponse FLATBUFFERS_FINAL_CLASS {
64+
private:
65+
int16_t ticks_l_;
66+
int16_t ticks_r_;
67+
68+
public:
69+
EncoderResponse() {
70+
memset(static_cast<void *>(this), 0, sizeof(EncoderResponse));
71+
}
72+
EncoderResponse(int16_t _ticks_l, int16_t _ticks_r)
73+
: ticks_l_(flatbuffers::EndianScalar(_ticks_l)),
74+
ticks_r_(flatbuffers::EndianScalar(_ticks_r)) {
75+
}
76+
int16_t ticks_l() const {
77+
return flatbuffers::EndianScalar(ticks_l_);
78+
}
79+
int16_t ticks_r() const {
80+
return flatbuffers::EndianScalar(ticks_r_);
81+
}
82+
};
83+
FLATBUFFERS_STRUCT_END(EncoderResponse, 4);
84+
85+
struct DataPackage FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table {
86+
typedef DataPackageBuilder Builder;
87+
enum FlatBuffersVTableOffset FLATBUFFERS_VTABLE_UNDERLYING_TYPE {
88+
VT_ENCODERREQUEST = 4,
89+
VT_ENCODERRESPONSE = 6,
90+
VT_TARGETSPEEDLREQUEST = 8,
91+
VT_TARGETSPEEDRREQUEST = 10
92+
};
93+
const noah::ros::EncoderRequest *encoderRequest() const {
94+
return GetStruct<const noah::ros::EncoderRequest *>(VT_ENCODERREQUEST);
95+
}
96+
const noah::ros::EncoderResponse *encoderResponse() const {
97+
return GetStruct<const noah::ros::EncoderResponse *>(VT_ENCODERRESPONSE);
98+
}
99+
float targetSpeedLRequest() const {
100+
return GetField<float>(VT_TARGETSPEEDLREQUEST, 0.0f);
101+
}
102+
float targetSpeedRRequest() const {
103+
return GetField<float>(VT_TARGETSPEEDRREQUEST, 0.0f);
104+
}
105+
bool Verify(flatbuffers::Verifier &verifier) const {
106+
return VerifyTableStart(verifier) &&
107+
VerifyField<noah::ros::EncoderRequest>(verifier, VT_ENCODERREQUEST) &&
108+
VerifyField<noah::ros::EncoderResponse>(verifier, VT_ENCODERRESPONSE) &&
109+
VerifyField<float>(verifier, VT_TARGETSPEEDLREQUEST) &&
110+
VerifyField<float>(verifier, VT_TARGETSPEEDRREQUEST) &&
111+
verifier.EndTable();
112+
}
113+
};
114+
115+
struct DataPackageBuilder {
116+
typedef DataPackage Table;
117+
flatbuffers::FlatBufferBuilder &fbb_;
118+
flatbuffers::uoffset_t start_;
119+
void add_encoderRequest(const noah::ros::EncoderRequest *encoderRequest) {
120+
fbb_.AddStruct(DataPackage::VT_ENCODERREQUEST, encoderRequest);
121+
}
122+
void add_encoderResponse(const noah::ros::EncoderResponse *encoderResponse) {
123+
fbb_.AddStruct(DataPackage::VT_ENCODERRESPONSE, encoderResponse);
124+
}
125+
void add_targetSpeedLRequest(float targetSpeedLRequest) {
126+
fbb_.AddElement<float>(DataPackage::VT_TARGETSPEEDLREQUEST, targetSpeedLRequest, 0.0f);
127+
}
128+
void add_targetSpeedRRequest(float targetSpeedRRequest) {
129+
fbb_.AddElement<float>(DataPackage::VT_TARGETSPEEDRREQUEST, targetSpeedRRequest, 0.0f);
130+
}
131+
explicit DataPackageBuilder(flatbuffers::FlatBufferBuilder &_fbb)
132+
: fbb_(_fbb) {
133+
start_ = fbb_.StartTable();
134+
}
135+
DataPackageBuilder &operator=(const DataPackageBuilder &);
136+
flatbuffers::Offset<DataPackage> Finish() {
137+
const auto end = fbb_.EndTable(start_);
138+
auto o = flatbuffers::Offset<DataPackage>(end);
139+
return o;
140+
}
141+
};
142+
143+
inline flatbuffers::Offset<DataPackage> CreateDataPackage(
144+
flatbuffers::FlatBufferBuilder &_fbb,
145+
const noah::ros::EncoderRequest *encoderRequest = 0,
146+
const noah::ros::EncoderResponse *encoderResponse = 0,
147+
float targetSpeedLRequest = 0.0f,
148+
float targetSpeedRRequest = 0.0f) {
149+
DataPackageBuilder builder_(_fbb);
150+
builder_.add_targetSpeedRRequest(targetSpeedRRequest);
151+
builder_.add_targetSpeedLRequest(targetSpeedLRequest);
152+
builder_.add_encoderResponse(encoderResponse);
153+
builder_.add_encoderRequest(encoderRequest);
154+
return builder_.Finish();
155+
}
156+
157+
inline const noah::ros::DataPackage *GetDataPackage(const void *buf) {
158+
return flatbuffers::GetRoot<noah::ros::DataPackage>(buf);
159+
}
160+
161+
inline const noah::ros::DataPackage *GetSizePrefixedDataPackage(const void *buf) {
162+
return flatbuffers::GetSizePrefixedRoot<noah::ros::DataPackage>(buf);
163+
}
164+
165+
inline bool VerifyDataPackageBuffer(
166+
flatbuffers::Verifier &verifier) {
167+
return verifier.VerifyBuffer<noah::ros::DataPackage>(nullptr);
168+
}
169+
170+
inline bool VerifySizePrefixedDataPackageBuffer(
171+
flatbuffers::Verifier &verifier) {
172+
return verifier.VerifySizePrefixedBuffer<noah::ros::DataPackage>(nullptr);
173+
}
174+
175+
inline void FinishDataPackageBuffer(
176+
flatbuffers::FlatBufferBuilder &fbb,
177+
flatbuffers::Offset<noah::ros::DataPackage> root) {
178+
fbb.Finish(root);
179+
}
180+
181+
inline void FinishSizePrefixedDataPackageBuffer(
182+
flatbuffers::FlatBufferBuilder &fbb,
183+
flatbuffers::Offset<noah::ros::DataPackage> root) {
184+
fbb.FinishSizePrefixed(root);
185+
}
186+
187+
} // namespace ros
188+
} // namespace noah
189+
190+
#endif // FLATBUFFERS_GENERATED_DATAPACKAGE_NOAH_ROS_H_

0 commit comments

Comments
 (0)