Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Handle and log onboard_computer_status messages #13169

Merged
merged 13 commits into from
Oct 27, 2019
1 change: 1 addition & 0 deletions msg/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,7 @@ set(msg_files
multirotor_motor_limits.msg
obstacle_distance.msg
offboard_control_mode.msg
onboard_computer_status.msg
optical_flow.msg
orbit_status.msg
parameter_update.msg
Expand Down
23 changes: 23 additions & 0 deletions msg/onboard_computer_status.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
# ONBOARD_COMPUTER_STATUS message data
uint64 timestamp # [us] time since system start (microseconds)
uint32 uptime # [ms] time since system boot of the companion (milliseconds)

uint8 type # type of onboard computer 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers.

uint8[8] cpu_cores # CPU usage on the component in percent
uint8[10] cpu_combined # Combined CPU usage as the last 10 slices of 100 MS
uint8[4] gpu_cores # GPU usage on the component in percent
uint8[10] gpu_combined # Combined GPU usage as the last 10 slices of 100 MS
int8 temperature_board # [degC] Temperature of the board
int8[8] temperature_core # [degC] Temperature of the CPU core
int16[4] fan_speed # [rpm] Fan speeds
uint32 ram_usage # [MB] Amount of used RAM on the component system
uint32 ram_total # [MB] Total amount of RAM on the component system
uint32[4] storage_type # Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable)
uint32[4] storage_usage # [MB] Amount of used storage space on the component system
uint32[4] storage_total # [MB] Total amount of storage space on the component system
uint32[6] link_type # [Kb/s] Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary
uint32[6] link_tx_rate # [Kb/s] Network traffic from the component system
uint32[6] link_rx_rate # [Kb/s] Network traffic to the component system
uint32[6] link_tx_max # [Kb/s] Network capacity from the component system
uint32[6] link_rx_max # [Kb/s] Network capacity to the component system
2 changes: 2 additions & 0 deletions msg/tools/uorb_rtps_message_ids.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -262,6 +262,8 @@ rtps:
id: 114
- msg: airspeed_validated
id: 115
- msg: onboard_computer_status
id: 116
########## multi topics: begin ##########
- msg: actuator_controls_0
id: 150
Expand Down
1 change: 1 addition & 0 deletions src/modules/logger/logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -639,6 +639,7 @@ void Logger::add_vision_and_avoidance_topics()
{
add_topic("collision_constraints");
add_topic("obstacle_distance_fused");
add_topic("onboard_computer_status", 200);
add_topic("vehicle_mocap_odometry", 30);
add_topic("vehicle_trajectory_waypoint", 200);
add_topic("vehicle_trajectory_waypoint_desired", 200);
Expand Down
39 changes: 39 additions & 0 deletions src/modules/mavlink/mavlink_receiver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -245,6 +245,10 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
handle_message_debug_float_array(msg);
break;

case MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS:
handle_message_onboard_computer_status(msg);
break;

default:
break;
}
Expand Down Expand Up @@ -2535,6 +2539,41 @@ MavlinkReceiver::handle_message_debug_float_array(mavlink_message_t *msg)
_debug_array_pub.publish(debug_topic);
}

void
MavlinkReceiver::handle_message_onboard_computer_status(mavlink_message_t *msg)
{
mavlink_onboard_computer_status_t status_msg;
mavlink_msg_onboard_computer_status_decode(msg, &status_msg);

onboard_computer_status_s onboard_computer_status_topic{};

onboard_computer_status_topic.timestamp = hrt_absolute_time();
onboard_computer_status_topic.uptime = status_msg.uptime;

onboard_computer_status_topic.type = status_msg.type;

memcpy(onboard_computer_status_topic.cpu_cores, status_msg.cpu_cores, sizeof(status_msg.cpu_cores));
memcpy(onboard_computer_status_topic.cpu_combined, status_msg.cpu_combined, sizeof(status_msg.cpu_combined));
memcpy(onboard_computer_status_topic.gpu_cores, status_msg.gpu_cores, sizeof(status_msg.gpu_cores));
memcpy(onboard_computer_status_topic.gpu_combined, status_msg.gpu_combined, sizeof(status_msg.gpu_combined));
onboard_computer_status_topic.temperature_board = status_msg.temperature_board;
memcpy(onboard_computer_status_topic.temperature_core, status_msg.temperature_core,
sizeof(status_msg.temperature_core));
memcpy(onboard_computer_status_topic.fan_speed, status_msg.fan_speed, sizeof(status_msg.fan_speed));
onboard_computer_status_topic.ram_usage = status_msg.ram_usage;
onboard_computer_status_topic.ram_total = status_msg.ram_total;
memcpy(onboard_computer_status_topic.storage_type, status_msg.storage_type, sizeof(status_msg.storage_type));
memcpy(onboard_computer_status_topic.storage_usage, status_msg.storage_usage, sizeof(status_msg.storage_usage));
memcpy(onboard_computer_status_topic.storage_total, status_msg.storage_total, sizeof(status_msg.storage_total));
memcpy(onboard_computer_status_topic.link_type, status_msg.link_type, sizeof(status_msg.link_type));
memcpy(onboard_computer_status_topic.link_tx_rate, status_msg.link_tx_rate, sizeof(status_msg.link_tx_rate));
memcpy(onboard_computer_status_topic.link_rx_rate, status_msg.link_rx_rate, sizeof(status_msg.link_rx_rate));
memcpy(onboard_computer_status_topic.link_tx_max, status_msg.link_tx_max, sizeof(status_msg.link_tx_max));
memcpy(onboard_computer_status_topic.link_rx_max, status_msg.link_rx_max, sizeof(status_msg.link_rx_max));

_onboard_computer_status_pub.publish(onboard_computer_status_topic);
}

/**
* Receive data from UART/UDP
*/
Expand Down
3 changes: 3 additions & 0 deletions src/modules/mavlink/mavlink_receiver.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,7 @@
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/obstacle_distance.h>
#include <uORB/topics/offboard_control_mode.h>
#include <uORB/topics/onboard_computer_status.h>
#include <uORB/topics/optical_flow.h>
#include <uORB/topics/ping.h>
#include <uORB/topics/position_setpoint_triplet.h>
Expand Down Expand Up @@ -165,6 +166,7 @@ class MavlinkReceiver : public ModuleParams
void handle_message_trajectory_representation_waypoints(mavlink_message_t *msg);
void handle_message_utm_global_position(mavlink_message_t *msg);
void handle_message_vision_position_estimate(mavlink_message_t *msg);
void handle_message_onboard_computer_status(mavlink_message_t *msg);


void Run();
Expand Down Expand Up @@ -227,6 +229,7 @@ class MavlinkReceiver : public ModuleParams
uORB::Publication<landing_target_pose_s> _landing_target_pose_pub{ORB_ID(landing_target_pose)};
uORB::Publication<obstacle_distance_s> _obstacle_distance_pub{ORB_ID(obstacle_distance)};
uORB::Publication<offboard_control_mode_s> _offboard_control_mode_pub{ORB_ID(offboard_control_mode)};
uORB::Publication<onboard_computer_status_s> _onboard_computer_status_pub{ORB_ID(onboard_computer_status)};
uORB::Publication<optical_flow_s> _flow_pub{ORB_ID(optical_flow)};
uORB::Publication<position_setpoint_triplet_s> _pos_sp_triplet_pub{ORB_ID(position_setpoint_triplet)};
uORB::Publication<vehicle_attitude_s> _attitude_pub{ORB_ID(vehicle_attitude)};
Expand Down