Skip to content

Commit

Permalink
Parameter update - Rename variables in modules/mavlink
Browse files Browse the repository at this point in the history
using parameter_update.py script
  • Loading branch information
bresch committed Mar 25, 2019
1 parent ab6681d commit cb8d598
Show file tree
Hide file tree
Showing 2 changed files with 30 additions and 30 deletions.
24 changes: 12 additions & 12 deletions src/modules/mavlink/mavlink_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -258,13 +258,13 @@ Mavlink::Mavlink() :
mavlink_update_parameters();

// save the current system- and component ID because we don't allow them to change during operation
int sys_id = _param_system_id.get();
int sys_id = _param_mav_sys_id.get();

if (sys_id > 0 && sys_id < 255) {
mavlink_system.sysid = sys_id;
}

int comp_id = _param_component_id.get();
int comp_id = _param_mav_comp_id.get();

if (comp_id > 0 && comp_id < 255) {
mavlink_system.compid = comp_id;
Expand Down Expand Up @@ -302,16 +302,16 @@ Mavlink::mavlink_update_parameters()
{
updateParams();

int32_t proto = _param_mav_proto_version.get();
int32_t proto = _param_mav_proto_ver.get();

if (_protocol_version_switch != proto) {
_protocol_version_switch = proto;
set_proto_version(proto);
}

if (_param_system_type.get() < 0 || _param_system_type.get() >= MAV_TYPE_ENUM_END) {
_param_system_type.set(0);
_param_system_type.commit_no_notification();
if (_param_mav_type.get() < 0 || _param_mav_type.get() >= MAV_TYPE_ENUM_END) {
_param_mav_type.set(0);
_param_mav_type.commit_no_notification();
PX4_ERR("MAV_TYPE parameter invalid, resetting to 0.");
}
}
Expand Down Expand Up @@ -2217,7 +2217,7 @@ Mavlink::task_main(int argc, char *argv[])

#if defined(CONFIG_NET)

if (_param_broadcast_mode.get() != BROADCAST_MODE_MULTICAST) {
if (_param_mav_broadcast.get() != BROADCAST_MODE_MULTICAST) {
_src_addr_initialized = false;
}

Expand Down Expand Up @@ -2564,7 +2564,7 @@ void Mavlink::publish_telemetry_status()
void Mavlink::check_radio_config()
{
/* radio config check */
if (_uart_fd >= 0 && _param_radio_id.get() != 0
if (_uart_fd >= 0 && _param_mav_radio_id.get() != 0
&& _tstatus.type == telemetry_status_s::LINK_TYPE_3DR_RADIO) {
/* request to configure radio and radio is present */
FILE *fs = fdopen(_uart_fd, "w");
Expand All @@ -2575,9 +2575,9 @@ void Mavlink::check_radio_config()
fprintf(fs, "+++\n");
px4_usleep(1200000);

if (_param_radio_id.get() > 0) {
if (_param_mav_radio_id.get() > 0) {
/* set channel */
fprintf(fs, "ATS3=%u\n", _param_radio_id.get());
fprintf(fs, "ATS3=%u\n", _param_mav_radio_id.get());
px4_usleep(200000);

} else {
Expand Down Expand Up @@ -2608,8 +2608,8 @@ void Mavlink::check_radio_config()
}

/* reset param and save */
_param_radio_id.set(0);
_param_radio_id.commit_no_notification();
_param_mav_radio_id.set(0);
_param_mav_radio_id.commit_no_notification();
}
}

Expand Down
36 changes: 18 additions & 18 deletions src/modules/mavlink/mavlink_main.h
Original file line number Diff line number Diff line change
Expand Up @@ -244,17 +244,17 @@ class Mavlink : public ModuleParams

bool get_hil_enabled() { return _hil_enabled; }

bool get_use_hil_gps() { return _param_use_hil_gps.get(); }
bool get_use_hil_gps() { return _param_mav_usehilgps.get(); }

bool get_forward_externalsp() { return _param_forward_externalsp.get(); }
bool get_forward_externalsp() { return _param_mav_fwdextsp.get(); }

bool get_flow_control_enabled() { return _flow_control_mode; }

bool get_forwarding_on() { return _forwarding_on; }

bool is_connected() { return (hrt_elapsed_time(&_tstatus.heartbeat_time) < 3_s); }

bool broadcast_enabled() { return _param_broadcast_mode.get() == BROADCAST_MODE_ON; }
bool broadcast_enabled() { return _param_mav_broadcast.get() == BROADCAST_MODE_ON; }

/**
* Set the boot complete flag on all instances
Expand Down Expand Up @@ -443,7 +443,7 @@ class Mavlink : public ModuleParams

ringbuffer::RingBuffer *get_logbuffer() { return &_logbuffer; }

unsigned get_system_type() { return _param_system_type.get(); }
unsigned get_system_type() { return _param_mav_type.get(); }

Protocol get_protocol() { return _protocol; }

Expand Down Expand Up @@ -504,9 +504,9 @@ class Mavlink : public ModuleParams

bool ftp_enabled() const { return _ftp_on; }

bool hash_check_enabled() const { return _param_hash_check_enabled.get(); }
bool forward_heartbeats_enabled() const { return _param_heartbeat_forwarding_enabled.get(); }
bool odometry_loopback_enabled() const { return _param_send_odom_loopback.get(); }
bool hash_check_enabled() const { return _param_mav_hash_chk_en.get(); }
bool forward_heartbeats_enabled() const { return _param_mav_hb_forw_en.get(); }
bool odometry_loopback_enabled() const { return _param_mav_odom_lp.get(); }

struct ping_statistics_s {
uint64_t last_ping_time;
Expand Down Expand Up @@ -646,17 +646,17 @@ class Mavlink : public ModuleParams
pthread_mutex_t _send_mutex {};

DEFINE_PARAMETERS(
(ParamInt<px4::params::MAV_SYS_ID>) _param_system_id,
(ParamInt<px4::params::MAV_COMP_ID>) _param_component_id,
(ParamInt<px4::params::MAV_PROTO_VER>) _param_mav_proto_version,
(ParamInt<px4::params::MAV_RADIO_ID>) _param_radio_id,
(ParamInt<px4::params::MAV_TYPE>) _param_system_type,
(ParamBool<px4::params::MAV_USEHILGPS>) _param_use_hil_gps,
(ParamBool<px4::params::MAV_FWDEXTSP>) _param_forward_externalsp,
(ParamInt<px4::params::MAV_BROADCAST>) _param_broadcast_mode,
(ParamBool<px4::params::MAV_HASH_CHK_EN>) _param_hash_check_enabled,
(ParamBool<px4::params::MAV_HB_FORW_EN>) _param_heartbeat_forwarding_enabled,
(ParamBool<px4::params::MAV_ODOM_LP>) _param_send_odom_loopback
(ParamInt<px4::params::MAV_SYS_ID>) _param_mav_sys_id,
(ParamInt<px4::params::MAV_COMP_ID>) _param_mav_comp_id,
(ParamInt<px4::params::MAV_PROTO_VER>) _param_mav_proto_ver,
(ParamInt<px4::params::MAV_RADIO_ID>) _param_mav_radio_id,
(ParamInt<px4::params::MAV_TYPE>) _param_mav_type,
(ParamBool<px4::params::MAV_USEHILGPS>) _param_mav_usehilgps,
(ParamBool<px4::params::MAV_FWDEXTSP>) _param_mav_fwdextsp,
(ParamInt<px4::params::MAV_BROADCAST>) _param_mav_broadcast,
(ParamBool<px4::params::MAV_HASH_CHK_EN>) _param_mav_hash_chk_en,
(ParamBool<px4::params::MAV_HB_FORW_EN>) _param_mav_hb_forw_en,
(ParamBool<px4::params::MAV_ODOM_LP>) _param_mav_odom_lp
)

perf_counter_t _loop_perf; /**< loop performance counter */
Expand Down

0 comments on commit cb8d598

Please sign in to comment.