Skip to content

Commit

Permalink
mavlink sort message defaults and float literal consistency
Browse files Browse the repository at this point in the history
  • Loading branch information
dagar committed Jan 14, 2019
1 parent 1e14b10 commit 63097bd
Showing 1 changed file with 23 additions and 23 deletions.
46 changes: 23 additions & 23 deletions src/modules/mavlink/mavlink_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1610,7 +1610,7 @@ Mavlink::update_rate_mult()
float mavlink_ulog_streaming_rate_inv = 1.0f;

if (_mavlink_ulog) {
mavlink_ulog_streaming_rate_inv = 1.f - _mavlink_ulog->current_data_rate();
mavlink_ulog_streaming_rate_inv = 1.0f - _mavlink_ulog->current_data_rate();
}

/* scale up and down as the link permits */
Expand Down Expand Up @@ -1692,7 +1692,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
}
};

const float unlimited_rate = -1.f;
const float unlimited_rate = -1.0f;

switch (_mode) {
case MAVLINK_MODE_NORMAL:
Expand All @@ -1703,32 +1703,32 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("CAMERA_IMAGE_CAPTURED", unlimited_rate);
configure_stream_local("COLLISION", unlimited_rate);
configure_stream_local("DEBUG", 1.0f);
configure_stream_local("DEBUG_VECT", 1.0f);
configure_stream_local("DEBUG_FLOAT_ARRAY", 1.0f);
configure_stream_local("DEBUG_VECT", 1.0f);
configure_stream_local("DISTANCE_SENSOR", 0.5f);
configure_stream_local("ESTIMATOR_STATUS", 0.5f);
configure_stream_local("EXTENDED_SYS_STATE", 1.0f);
configure_stream_local("GLOBAL_POSITION_INT", 5.0f);
configure_stream_local("GPS_RAW_INT", 1.0f);
configure_stream_local("GPS2_RAW", 1.0f);
configure_stream_local("GPS_RAW_INT", 1.0f);
configure_stream_local("HIGHRES_IMU", 1.5f);
configure_stream_local("HOME_POSITION", 0.5f);
configure_stream_local("LOCAL_POSITION_NED", 1.0f);
configure_stream_local("NAMED_VALUE_FLOAT", 1.0f);
configure_stream_local("NAV_CONTROLLER_OUTPUT", 1.5f);
configure_stream_local("ODOMETRY", 3.0f);
configure_stream_local("OPTICAL_FLOW_RAD", 1.0f);
configure_stream_local("ORBIT_EXECUTION_STATUS", 5.0f);
configure_stream_local("PING", 0.1f);
configure_stream_local("POSITION_TARGET_LOCAL_NED", 1.5f);
configure_stream_local("POSITION_TARGET_GLOBAL_INT", 1.5f);
configure_stream_local("POSITION_TARGET_LOCAL_NED", 1.5f);
configure_stream_local("RC_CHANNELS", 5.0f);
configure_stream_local("SERVO_OUTPUT_RAW_0", 1.0f);
configure_stream_local("SYS_STATUS", 1.0f);
configure_stream_local("TRAJECTORY_REPRESENTATION_WAYPOINTS", 5.0f);
configure_stream_local("UTM_GLOBAL_POSITION", 1.0f);
configure_stream_local("VFR_HUD", 4.0f);
configure_stream_local("ODOMETRY", 3.0f);
configure_stream_local("WIND_COV", 1.0f);
configure_stream_local("ORBIT_EXECUTION_STATUS", 5.f);
break;

case MAVLINK_MODE_ONBOARD:
Expand All @@ -1743,20 +1743,22 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("CAMERA_TRIGGER", unlimited_rate);
configure_stream_local("COLLISION", unlimited_rate);
configure_stream_local("DEBUG", 10.0f);
configure_stream_local("DEBUG_VECT", 10.0f);
configure_stream_local("DEBUG_FLOAT_ARRAY", 10.0f);
configure_stream_local("DEBUG_VECT", 10.0f);
configure_stream_local("DISTANCE_SENSOR", 10.0f);
configure_stream_local("ESTIMATOR_STATUS", 1.0f);
configure_stream_local("EXTENDED_SYS_STATE", 5.0f);
configure_stream_local("GLOBAL_POSITION_INT", 50.0f);
configure_stream_local("GPS_RAW_INT", unlimited_rate);
configure_stream_local("GPS2_RAW", unlimited_rate);
configure_stream_local("GPS_RAW_INT", unlimited_rate);
configure_stream_local("HIGHRES_IMU", 50.0f);
configure_stream_local("HOME_POSITION", 0.5f);
configure_stream_local("LOCAL_POSITION_NED", 30.0f);
configure_stream_local("NAMED_VALUE_FLOAT", 10.0f);
configure_stream_local("NAV_CONTROLLER_OUTPUT", 10.0f);
configure_stream_local("ODOMETRY", 30.0f);
configure_stream_local("OPTICAL_FLOW_RAD", 10.0f);
configure_stream_local("ORBIT_EXECUTION_STATUS", 5.0f);
configure_stream_local("PING", 1.0f);
configure_stream_local("POSITION_TARGET_GLOBAL_INT", 10.0f);
configure_stream_local("POSITION_TARGET_LOCAL_NED", 10.0f);
Expand All @@ -1769,9 +1771,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("TRAJECTORY_REPRESENTATION_WAYPOINTS", 5.0f);
configure_stream_local("UTM_GLOBAL_POSITION", 1.0f);
configure_stream_local("VFR_HUD", 10.0f);
configure_stream_local("ODOMETRY", 30.0f);
configure_stream_local("WIND_COV", 10.0f);
configure_stream_local("ORBIT_EXECUTION_STATUS", 5.f);
break;

case MAVLINK_MODE_OSD:
Expand Down Expand Up @@ -1804,27 +1804,29 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("ADSB_VEHICLE", unlimited_rate);
configure_stream_local("ALTITUDE", 10.0f);
configure_stream_local("ATTITUDE", 50.0f);
configure_stream_local("ATTITUDE_TARGET", 8.0f);
configure_stream_local("ATTITUDE_QUATERNION", 50.0f);
configure_stream_local("CAMERA_TRIGGER", unlimited_rate);
configure_stream_local("ATTITUDE_TARGET", 8.0f);
configure_stream_local("CAMERA_IMAGE_CAPTURED", unlimited_rate);
configure_stream_local("CAMERA_TRIGGER", unlimited_rate);
configure_stream_local("COLLISION", unlimited_rate);
configure_stream_local("DEBUG", 50.0f);
configure_stream_local("DEBUG_VECT", 50.0f);
configure_stream_local("DEBUG_FLOAT_ARRAY", 50.0f);
configure_stream_local("DEBUG_VECT", 50.0f);
configure_stream_local("DISTANCE_SENSOR", 10.0f);
configure_stream_local("GPS_RAW_INT", unlimited_rate);
configure_stream_local("GPS2_RAW", unlimited_rate);
configure_stream_local("ESTIMATOR_STATUS", 5.0f);
configure_stream_local("EXTENDED_SYS_STATE", 2.0f);
configure_stream_local("GLOBAL_POSITION_INT", 10.0f);
configure_stream_local("GPS2_RAW", unlimited_rate);
configure_stream_local("GPS_RAW_INT", unlimited_rate);
configure_stream_local("HIGHRES_IMU", 50.0f);
configure_stream_local("HOME_POSITION", 0.5f);
configure_stream_local("LOCAL_POSITION_NED", 30.0f);
configure_stream_local("MANUAL_CONTROL", 5.0f);
configure_stream_local("NAMED_VALUE_FLOAT", 50.0f);
configure_stream_local("NAV_CONTROLLER_OUTPUT", 10.0f);
configure_stream_local("ODOMETRY", 30.0f);
configure_stream_local("OPTICAL_FLOW_RAD", 10.0f);
configure_stream_local("ORBIT_EXECUTION_STATUS", 5.0f);
configure_stream_local("PING", 1.0f);
configure_stream_local("POSITION_TARGET_GLOBAL_INT", 10.0f);
configure_stream_local("RC_CHANNELS", 10.0f);
Expand All @@ -1835,9 +1837,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("TIMESYNC", 10.0f);
configure_stream_local("UTM_GLOBAL_POSITION", 1.0f);
configure_stream_local("VFR_HUD", 20.0f);
configure_stream_local("ODOMETRY", 30.0f);
configure_stream_local("WIND_COV", 10.0f);
configure_stream_local("ORBIT_EXECUTION_STATUS", 5.f);
break;

case MAVLINK_MODE_IRIDIUM:
Expand All @@ -1848,8 +1848,8 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("ALTITUDE", 0.5f);
configure_stream_local("ATTITUDE", 10.0f);
configure_stream_local("EXTENDED_SYS_STATE", 0.1f);
configure_stream_local("GPS_RAW_INT", 0.5f);
configure_stream_local("GLOBAL_POSITION_INT", 5.0f);
configure_stream_local("GPS_RAW_INT", 0.5f);
configure_stream_local("HOME_POSITION", 0.1f);
configure_stream_local("NAMED_VALUE_FLOAT", 1.0f);
configure_stream_local("RC_CHANNELS", 0.5f);
Expand All @@ -1864,7 +1864,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)

if (configure_single_stream && !stream_configured && strcmp(configure_single_stream, "HEARTBEAT") != 0) {
// stream was not found, assume it is disabled by default
return configure_stream(configure_single_stream, 0.f);
return configure_stream(configure_single_stream, 0.0f);
}

return ret;
Expand Down Expand Up @@ -2948,8 +2948,8 @@ Mavlink::stream_command(int argc, char *argv[])
return 1;
}

if (rate < 0.f) {
rate = -2.f; // use default rate
if (rate < 0.0f) {
rate = -2.0f; // use default rate
}

if (inst != nullptr) {
Expand Down Expand Up @@ -3061,7 +3061,7 @@ Start mavlink on UDP port 14556 and enable the HIGHRES_IMU message with 50Hz:
#endif
PRINT_MODULE_USAGE_PARAM_STRING('d', nullptr, "<file:dev>", "Select Mavlink instance via Serial Device", true);
PRINT_MODULE_USAGE_PARAM_STRING('s', nullptr, nullptr, "Mavlink stream to configure", false);
PRINT_MODULE_USAGE_PARAM_FLOAT('r', -1.f, 0.f, 2000.f, "Rate in Hz (0 = turn off, -1 = set to default)", false);
PRINT_MODULE_USAGE_PARAM_FLOAT('r', -1.0f, 0.0f, 2000.0f, "Rate in Hz (0 = turn off, -1 = set to default)", false);

PRINT_MODULE_USAGE_COMMAND_DESCR("boot_complete",
"Enable sending of messages. (Must be) called as last step in startup script.");
Expand Down

0 comments on commit 63097bd

Please sign in to comment.