forked from aletty/roscopter
-
Notifications
You must be signed in to change notification settings - Fork 19
Exploring Param Control
Josh Weaver edited this page Feb 22, 2014
·
3 revisions
Parameters may be sent through MAVLink following Parameter Protocol.
Initially, parameters may be read in using:
master.mav.param_request_list_send(master.target_system, master.target_component)
The PARAM_VALUE message will be returned holding characteristics about all params
- param_id: name of the parameter stored on the device
- param_value: value of the parameter
- param_type: type of the value stored for the parameter (defined by MAV_PARAM_TYPE
- param_count: Total number of parameters
- param_index: Index of current parameters out of all parameters
Following the Parameter Protocol, a parameter may be sent using the "param_set_send" function:
def param_set_send(self, target_system, target_component, param_id, param_value, param_type):
'''
Set a parameter value TEMPORARILY to RAM. It will be reset to default
on system reboot. Send the ACTION
MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM
contents to EEPROM. IMPORTANT: The receiving component
should acknowledge the new parameter value by sending
a param_value message to all communication partners.
This will also ensure that multiple GCS all have an
up-to-date list of all parameters. If the sending GCS
did not receive a PARAM_VALUE message within its
timeout time, it should re-send the PARAM_SET message.
target_system : System ID (uint8_t)
target_component : Component ID (uint8_t)
param_id : Onboard parameter id (char)
param_value : Onboard parameter value (float)
param_type : Onboard parameter type: see MAV_VAR enum (uint8_t)
'''
return self.send(self.param_set_encode(target_system, target_component, param_id, param_value, param_type))
When a param is sent, the PARAM_VALUE message will be returned with the changes made to the variable. To store this param directly to ROM, the ACTION MAV_ACTION_STORAGE_WRITE must be sent. This is done using:
master.mav.command_long_send(master.target_system, master.target_component,
mavutil.mavlink.MAV_CMD_PREFLIGHT_STORAGE, 0, 0, 0, 0, 0, 0, 0, 0)
- WPNAV_RADIUS: radius for position accuracy used for waypoints. Waypoint structure defines as mm, value passed in is cm. Result is /10.