diff --git a/CMakeLists.txt b/CMakeLists.txt
index 2aa7f85..e2962a2 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -7,9 +7,11 @@ endif()
# find dependencies
find_package(ament_cmake REQUIRED)
+find_package(geometry_msgs REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclpy REQUIRED)
find_package(rosidl_default_generators REQUIRED)
+find_package(sensor_msgs REQUIRED)
find_package(std_msgs REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
@@ -48,7 +50,10 @@ rosidl_generate_interfaces(${PROJECT_NAME}
"srv/TFSetStateMachineCommand.srv"
"srv/TFWatchDogCommand.srv"
"srv/ValveCommand.srv"
- DEPENDENCIES std_msgs
+ DEPENDENCIES
+ geometry_msgs
+ sensor_msgs
+ std_msgs
ADD_LINTER_TESTS
)
diff --git a/README.md b/README.md
index ae6fb85..962af8a 100644
--- a/README.md
+++ b/README.md
@@ -10,31 +10,31 @@ Collection of telemetry (feedback) from buoy sensors and microcontrollers.
### Telemetry
Telemetry data from sensors available per microcontroller
-- type: `BCRecord`
- topic: `/bc_record`
+- type: `BCRecord`
+ topic: `/bc_record`
Description: (TODO) battery data
-
-- type: `PCRecord`
- topic: `/pc_record`
+
+- type: `PCRecord`
+ topic: `/pc_record`
Description: (TODO) power controller data
-
-- type: `SCRecord`
- topic: `/sc_record`
+
+- type: `SCRecord`
+ topic: `/sc_record`
Description: (TODO) spring controller data
-
-- type: `TFRecord`
- topic: `/tf_record`
+
+- type: `TFRecord`
+ topic: `/tf_record`
Description: (TODO) trefoil data
-
-- type: `XBRecord`
- topic: `/xb_record`
+
+- type: `XBRecord`
+ topic: `/xb_record`
Description: (TODO) Crossbow AHRS data
### Consolidated (Time-Synchronized) Telemetry
Snapshot in time of all data from the buoy.
-- type: `PBRecord`
- topic: `/pb_record`
+- type: `PBRecord`
+ topic: `/pb_record`
Description: TODO
## Services (.srv)
@@ -43,143 +43,143 @@ Collection of commands to configure/control the Power Buoy.
### Power Microcontroller
Services available to configure the Power Microcontroller.
-- type: `PCBattSwitchCommand`
- topic: `/pc_batt_switch_command`
- args: OFF, ON (enum)
- Description: TODO
-
-- type: `PCBiasCurrCommand`
- topic: `/pc_bias_curr_command`
- args: -15.0 to +15.0 (float, amps)
- Description: TODO
-
-- type: `PCChargeCurrLimCommand`
- topic: `/pc_charge_curr_lim_command`
- args: 2.0 to 12.0 (float, amps)
- Description: TODO
-
-- type: `PCDrawCurrLimCommand`
- topic: `/pc_draw_curr_lim_command`
- args: 2.0 to 12.0 (float, amps)
- Description: TODO
-
-- type: `PCPackRateCommand`
- topic: `/pc_pack_rate_command`
- args: 10 to 50 (int, hz)
+- type: `PCBattSwitchCommand`
+ topic: `/pc_batt_switch_command`
+ args: OFF, ON (enum)
+ Description: TODO
+
+- type: `PCBiasCurrCommand`
+ topic: `/pc_bias_curr_command`
+ args: -15.0 to +15.0 (float, amps)
+ Description: TODO
+
+- type: `PCChargeCurrLimCommand`
+ topic: `/pc_charge_curr_lim_command`
+ args: 2.0 to 12.0 (float, amps)
+ Description: TODO
+
+- type: `PCDrawCurrLimCommand`
+ topic: `/pc_draw_curr_lim_command`
+ args: 2.0 to 12.0 (float, amps)
+ Description: TODO
+
+- type: `PCPackRateCommand`
+ topic: `/pc_pack_rate_command`
+ args: 10 to 50 (int, hz)
Description: set PCRecord publish rate in Hz
-
-- type: `PCRetractCommand`
- topic: `/pc_retract_command`
- args: 0.4 to 1.0 (float)
+
+- type: `PCRetractCommand`
+ topic: `/pc_retract_command`
+ args: 0.4 to 1.0 (float)
Description: TODO
-
-- type: `PCScaleCommand`
- topic: `/pc_scale_command`
- args: 0.5 to 1.4 (float)
+
+- type: `PCScaleCommand`
+ topic: `/pc_scale_command`
+ args: 0.5 to 1.4 (float)
Description: TODO
-
-- type: `PCStdDevTargCommand`
- topic: `/pc_std_dev_targ_command`
- args: 0 to 2000 (int)
+
+- type: `PCStdDevTargCommand`
+ topic: `/pc_std_dev_targ_command`
+ args: 0 to 2000 (int)
Description: TODO
-
-- type: `PCVTargMaxCommand`
- topic: `/pc_v_targ_max_command`
- args: 320.0 to 330.0 (float, volts)
+
+- type: `PCVTargMaxCommand`
+ topic: `/pc_v_targ_max_command`
+ args: 320.0 to 330.0 (float, volts)
Description: TODO
-
-- type: `PCWindCurrCommand`
- topic: `/pc_wind_curr_command`
- args: -35.0 to 35.0 (float, amps)
+
+- type: `PCWindCurrCommand`
+ topic: `/pc_wind_curr_command`
+ args: -35.0 to 35.0 (float, amps)
Description: TODO
-
-- type: `GainCommand`
- topic: `/gain_command`
- args: OFF, 1 to 200 (enum or int)
+
+- type: `GainCommand`
+ topic: `/gain_command`
+ args: OFF, 1 to 200 (enum or int)
Description: TODO
### Battery Microcontroller
Services available to configure the Battery Microcontroller.
-- type: `BCResetCommand`
- topic: `/bc_reset_command`
- args: None
+- type: `BCResetCommand`
+ topic: `/bc_reset_command`
+ args: None
Description: TODO
### Spring Microcontroller
-- type: `SCPackRateCommand`
- topic: `/sc_pack_rate_command`
- args: 10 to 50 (int, hz)
+- type: `SCPackRateCommand`
+ topic: `/sc_pack_rate_command`
+ args: 10 to 50 (int, hz)
Description: set SCRecord publish rate in Hz
-
-- type: `SCResetCommand`
- topic: `/sc_reset_command`
- args: None
+
+- type: `SCResetCommand`
+ topic: `/sc_reset_command`
+ args: None
Description: TODO
-
-- type: `ValveCommand`
- topic: `/valve_command`
- args: OFF, 1 to 127 (enum or int, seconds)
+
+- type: `ValveCommand`
+ topic: `/valve_command`
+ args: OFF, 1 to 127 (enum or int, seconds)
Description: TODO
-
-- type: `PumpCommand`
- topic: `/pump_command`
- args: OFF, 1 to 127 (enum or int, seconds)
+
+- type: `PumpCommand`
+ topic: `/pump_command`
+ args: OFF, 1 to 127 (enum or int, seconds)
Description: TODO
-
-- type: `BenderCommand`
- topic: `/bender_command`
- args: OFF, ON, AUTO (enum)
+
+- type: `BenderCommand`
+ topic: `/bender_command`
+ args: OFF, ON, AUTO (enum)
Description: TODO
-
-- type: `TetherCommand`
- topic: `/tether_command`
- args: OFF, ON (enum)
+
+- type: `TetherCommand`
+ topic: `/tether_command`
+ args: OFF, ON (enum)
Description: TODO
### Trefoil Microcontroller
Services available to configure the Trefoil.
-- type: `TFResetCommand`
- topic: `/tf_reset_command`
- args: None
- Description: TODO
-
-- type: `TFSetActualPosCommand`
- topic: `/tf_set_actual_pos_command`
- args: OPEN, CLOSED (enum)
- Description: TODO
-
-- type: `TFSetChargeModeCommand`
- topic: `/tf_set_charge_mode_command`
- args: OFF, ON, AUTO_TIME, AUTO_VOLTAGE (enum)
- Description: TODO
-
-- type: `TFSetCurrLimCommand`
- topic: `/tf_set_curr_lim_command`
- args: 500 to 5000 (int, TODO(units))
- Description: TODO
-
-- type: `TFSetModeCommand`
- topic: `/tf_set_mode_command`
- args: POWER_10W, MONITOR_POS, HOLD_POS (enum)
- Description: TODO
-
-- type: `TFSetPosCommand`
- topic: `/tf_set_pos_command`
- args: OPEN, CLOSED (enum)
- Description: TODO
-
-- type: `TFSetStateMachineCommand`
- topic: `/tf_set_state_machine_command`
- args: HOME_MOVE, VEL_MOVE (enum)
- Description: TODO
-
-- type: `TFWatchDogCommand`
- topic: `/tf_watchdog_command`
- args: None
- Description: TODO
-
+- type: `TFResetCommand`
+ topic: `/tf_reset_command`
+ args: None
+ Description: TODO
+
+- type: `TFSetActualPosCommand`
+ topic: `/tf_set_actual_pos_command`
+ args: OPEN, CLOSED (enum)
+ Description: TODO
+
+- type: `TFSetChargeModeCommand`
+ topic: `/tf_set_charge_mode_command`
+ args: OFF, ON, AUTO_TIME, AUTO_VOLTAGE (enum)
+ Description: TODO
+
+- type: `TFSetCurrLimCommand`
+ topic: `/tf_set_curr_lim_command`
+ args: 500 to 5000 (int, TODO(units))
+ Description: TODO
+
+- type: `TFSetModeCommand`
+ topic: `/tf_set_mode_command`
+ args: POWER_10W, MONITOR_POS, HOLD_POS (enum)
+ Description: TODO
+
+- type: `TFSetPosCommand`
+ topic: `/tf_set_pos_command`
+ args: OPEN, CLOSED (enum)
+ Description: TODO
+
+- type: `TFSetStateMachineCommand`
+ topic: `/tf_set_state_machine_command`
+ args: HOME_MOVE, VEL_MOVE (enum)
+ Description: TODO
+
+- type: `TFWatchDogCommand`
+ topic: `/tf_watchdog_command`
+ args: None
+ Description: TODO
+
## Quality Declaration
diff --git a/msg/XBRecord.msg b/msg/XBRecord.msg
index 6ef6371..ef39e67 100644
--- a/msg/XBRecord.msg
+++ b/msg/XBRecord.msg
@@ -1,26 +1,19 @@
-#Crossbow AHRS
+# Crossbow AHRS
-std_msgs/Header header # timestamp, seq_num
+# Timestamp, seq_num
+std_msgs/Header header
-float32 roll_angle # Radians -pi to +pi
-float32 pitch_angle # Radians -pi to +pi
-float32 yaw_angle_true # (true north) Radians -pi to +pi
+# IMU data
+# * orientation expressed as a quaternion (radians)
+# * angular velocity (rad/s)
+# * linear acceleration (m/s^2, not in g)
+sensor_msgs/Imu imu
-float32 x_rate_corrected # Corrected X angular rate, rads/sec
-float32 y_rate_corrected # Corrected Y angular rate, rads/sec
-float32 z_rate_corrected # Corrected Z angular rate, rads/sec
+# GPS latitude, longitude, altitude
+sensor_msgs/NavSatFix gps
-float32 x_accel # X accelerometer, g
-float32 y_accel # Y accelerometer, g
-float32 z_accel # Z accelerometer, g
-
-float32 n_velocity # North velocity, m/s
-float32 e_velocity # East velocity, m/s
-float32 d_velocity # Down velocity, m/s
-
-float32 longitude # GPS longitude, radians
-float32 latitude # GPS latitude, radians
-float32 altitude # GPS altitude, meters (-100 to 16284)
-
-float32 x_rate_temp # X rate temperature, C
+# Linear velocity expressed in North-East-Down frame, in m/s
+geometry_msgs/Vector3 ned_velocity
+# X rate temperature, C
+sensor_msgs/Temperature x_rate_temp
diff --git a/package.xml b/package.xml
index d014bb4..4e87921 100644
--- a/package.xml
+++ b/package.xml
@@ -9,14 +9,16 @@
ament_cmake
ament_cmake_python
-
+
rclcpp
rclpy
-
+
rosidl_default_generators
rosidl_default_runtime
- std_msgs
+ geometry_msgs
+ std_msgs
+ sensor_msgs
ament_lint_auto
ament_lint_common