mavlink: handle receiving GENERATOR_STATUS

- only published (ORB_ID(generator_status)) and logged for now
This commit is contained in:
Daniel Agar 2020-09-25 11:36:58 -04:00 committed by GitHub
parent c57a48682e
commit 861e06dfd7
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
6 changed files with 81 additions and 4 deletions

View File

@ -65,6 +65,7 @@ set(msg_files
estimator_states.msg
estimator_status.msg
follow_target.msg
generator_status.msg
geofence_result.msg
gps_dump.msg
gps_inject_data.msg

44
msg/generator_status.msg Normal file
View File

@ -0,0 +1,44 @@
uint64 timestamp # time since system start (microseconds)
uint64 STATUS_FLAG_OFF = 1 # Generator is off.
uint64 STATUS_FLAG_READY = 2 # Generator is ready to start generating power.
uint64 STATUS_FLAG_GENERATING = 4 # Generator is generating power.
uint64 STATUS_FLAG_CHARGING = 8 # Generator is charging the batteries (generating enough power to charge and provide the load).
uint64 STATUS_FLAG_REDUCED_POWER = 16 # Generator is operating at a reduced maximum power.
uint64 STATUS_FLAG_MAXPOWER = 32 # Generator is providing the maximum output.
uint64 STATUS_FLAG_OVERTEMP_WARNING = 64 # Generator is near the maximum operating temperature, cooling is insufficient.
uint64 STATUS_FLAG_OVERTEMP_FAULT = 128 # Generator hit the maximum operating temperature and shutdown.
uint64 STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING = 256 # Power electronics are near the maximum operating temperature, cooling is insufficient.
uint64 STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT = 512 # Power electronics hit the maximum operating temperature and shutdown.
uint64 STATUS_FLAG_ELECTRONICS_FAULT = 1024 # Power electronics experienced a fault and shutdown.
uint64 STATUS_FLAG_POWERSOURCE_FAULT = 2048 # The power source supplying the generator failed e.g. mechanical generator stopped, tether is no longer providing power, solar cell is in shade, hydrogen reaction no longer happening.
uint64 STATUS_FLAG_COMMUNICATION_WARNING = 4096 # Generator controller having communication problems.
uint64 STATUS_FLAG_COOLING_WARNING = 8192 # Power electronic or generator cooling system error.
uint64 STATUS_FLAG_POWER_RAIL_FAULT = 16384 # Generator controller power rail experienced a fault.
uint64 STATUS_FLAG_OVERCURRENT_FAULT = 32768 # Generator controller exceeded the overcurrent threshold and shutdown to prevent damage.
uint64 STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT = 65536 # Generator controller detected a high current going into the batteries and shutdown to prevent battery damage. |
uint64 STATUS_FLAG_OVERVOLTAGE_FAULT = 131072 # Generator controller exceeded it's overvoltage threshold and shutdown to prevent it exceeding the voltage rating.
uint64 STATUS_FLAG_BATTERY_UNDERVOLT_FAULT = 262144 # Batteries are under voltage (generator will not start).
uint64 STATUS_FLAG_START_INHIBITED = 524288 # Generator start is inhibited by e.g. a safety switch.
uint64 STATUS_FLAG_MAINTENANCE_REQUIRED = 1048576 # Generator requires maintenance.
uint64 STATUS_FLAG_WARMING_UP = 2097152 # Generator is not ready to generate yet.
uint64 STATUS_FLAG_IDLE = 4194304 # Generator is idle.
uint64 status # Status flags
float32 battery_current # [A] Current into/out of battery. Positive for out. Negative for in. NaN: field not provided.
float32 load_current # [A] Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided
float32 power_generated # [W] The power being generated. NaN: field not provided
float32 bus_voltage # [V] Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus.
float32 bat_current_setpoint # [A] The target battery current. Positive for out. Negative for in. NaN: field not provided
uint32 runtime # [s] Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided.
int32 time_until_maintenance # [s] Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided.
uint16 generator_speed # [rpm] Speed of electrical generator or alternator. UINT16_MAX: field not provided.
int16 rectifier_temperature # [degC] The temperature of the rectifier or power converter. INT16_MAX: field not provided.
int16 generator_temperature # [degC] The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided.

View File

@ -283,6 +283,8 @@ rtps:
id: 134
- msg: estimator_states
id: 135
- msg: generator_status
id: 136
########## multi topics: begin ##########
- msg: actuator_controls_0
id: 150

View File

@ -63,6 +63,7 @@ void LoggedTopics::add_default_topics()
add_topic("estimator_sensor_bias", 1000);
add_topic("estimator_states", 1000);
add_topic("estimator_status", 200);
add_topic("generator_status");
add_topic("home_position");
add_topic("hover_thrust_estimate", 100);
add_topic("input_rc", 500);
@ -79,9 +80,9 @@ void LoggedTopics::add_default_topics()
add_topic("safety");
add_topic("sensor_combined");
add_topic("sensor_correction");
add_topic("sensors_status_imu", 200);
add_topic("sensor_preflight_mag", 500);
add_topic("sensor_selection");
add_topic("sensors_status_imu", 200);
add_topic("system_power", 500);
add_topic("tecs_status", 200);
add_topic("test_motor", 500);

View File

@ -267,6 +267,10 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
handle_message_onboard_computer_status(msg);
break;
case MAVLINK_MSG_ID_GENERATOR_STATUS:
handle_message_generator_status(msg);
break;
case MAVLINK_MSG_ID_STATUSTEXT:
handle_message_statustext(msg);
break;
@ -2780,6 +2784,28 @@ MavlinkReceiver::handle_message_onboard_computer_status(mavlink_message_t *msg)
_onboard_computer_status_pub.publish(onboard_computer_status_topic);
}
void MavlinkReceiver::handle_message_generator_status(mavlink_message_t *msg)
{
mavlink_generator_status_t status_msg;
mavlink_msg_generator_status_decode(msg, &status_msg);
generator_status_s generator_status{};
generator_status.timestamp = hrt_absolute_time();
generator_status.status = status_msg.status;
generator_status.battery_current = status_msg.battery_current;
generator_status.load_current = status_msg.load_current;
generator_status.power_generated = status_msg.power_generated;
generator_status.bus_voltage = status_msg.bus_voltage;
generator_status.bat_current_setpoint = status_msg.bat_current_setpoint;
generator_status.runtime = status_msg.runtime;
generator_status.time_until_maintenance = status_msg.time_until_maintenance;
generator_status.generator_speed = status_msg.generator_speed;
generator_status.rectifier_temperature = status_msg.rectifier_temperature;
generator_status.generator_temperature = status_msg.generator_temperature;
_generator_status_pub.publish(generator_status);
}
void MavlinkReceiver::handle_message_statustext(mavlink_message_t *msg)
{
if (msg->sysid == mavlink_system.sysid) {

View File

@ -69,6 +69,7 @@
#include <uORB/topics/differential_pressure.h>
#include <uORB/topics/distance_sensor.h>
#include <uORB/topics/follow_target.h>
#include <uORB/topics/generator_status.h>
#include <uORB/topics/gps_inject_data.h>
#include <uORB/topics/home_position.h>
#include <uORB/topics/input_rc.h>
@ -148,6 +149,7 @@ private:
void handle_message_debug_vect(mavlink_message_t *msg);
void handle_message_distance_sensor(mavlink_message_t *msg);
void handle_message_follow_target(mavlink_message_t *msg);
void handle_message_generator_status(mavlink_message_t *msg);
void handle_message_gps_global_origin(mavlink_message_t *msg);
void handle_message_gps_rtcm_data(mavlink_message_t *msg);
void handle_message_heartbeat(mavlink_message_t *msg);
@ -161,6 +163,7 @@ private:
void handle_message_named_value_float(mavlink_message_t *msg);
void handle_message_obstacle_distance(mavlink_message_t *msg);
void handle_message_odometry(mavlink_message_t *msg);
void handle_message_onboard_computer_status(mavlink_message_t *msg);
void handle_message_optical_flow_rad(mavlink_message_t *msg);
void handle_message_ping(mavlink_message_t *msg);
void handle_message_play_tune(mavlink_message_t *msg);
@ -171,14 +174,13 @@ private:
void handle_message_set_actuator_control_target(mavlink_message_t *msg);
void handle_message_set_attitude_target(mavlink_message_t *msg);
void handle_message_set_mode(mavlink_message_t *msg);
void handle_message_set_position_target_local_ned(mavlink_message_t *msg);
void handle_message_set_position_target_global_int(mavlink_message_t *msg);
void handle_message_set_position_target_local_ned(mavlink_message_t *msg);
void handle_message_statustext(mavlink_message_t *msg);
void handle_message_trajectory_representation_bezier(mavlink_message_t *msg);
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();
@ -245,6 +247,7 @@ private:
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<generator_status_s> _generator_status_pub{ORB_ID(generator_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)};