2012-08-04 19:12:36 -03:00
|
|
|
/****************************************************************************
|
|
|
|
*
|
2012-08-20 04:07:33 -03:00
|
|
|
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
|
|
|
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
2012-08-04 19:12:36 -03:00
|
|
|
*
|
|
|
|
* Redistribution and use in source and binary forms, with or without
|
|
|
|
* modification, are permitted provided that the following conditions
|
|
|
|
* are met:
|
|
|
|
*
|
|
|
|
* 1. Redistributions of source code must retain the above copyright
|
|
|
|
* notice, this list of conditions and the following disclaimer.
|
|
|
|
* 2. Redistributions in binary form must reproduce the above copyright
|
|
|
|
* notice, this list of conditions and the following disclaimer in
|
|
|
|
* the documentation and/or other materials provided with the
|
|
|
|
* distribution.
|
|
|
|
* 3. Neither the name PX4 nor the names of its contributors may be
|
|
|
|
* used to endorse or promote products derived from this software
|
|
|
|
* without specific prior written permission.
|
|
|
|
*
|
|
|
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
|
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
|
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
|
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
|
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
|
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
|
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
|
|
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
|
|
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
|
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
|
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
|
|
* POSSIBILITY OF SUCH DAMAGE.
|
|
|
|
*
|
|
|
|
****************************************************************************/
|
|
|
|
|
|
|
|
/**
|
|
|
|
* @file mavlink_parameters.h
|
|
|
|
* MAVLink parameter protocol definitions (BSD-relicensed).
|
|
|
|
*/
|
|
|
|
|
|
|
|
/* This assumes you have the mavlink headers on your include path
|
|
|
|
or in the same folder as this source file */
|
|
|
|
|
|
|
|
|
|
|
|
#include "v1.0/common/mavlink.h"
|
|
|
|
#include <stdbool.h>
|
2012-08-20 04:07:33 -03:00
|
|
|
#include <systemlib/param/param.h>
|
2012-08-04 19:12:36 -03:00
|
|
|
|
2012-08-20 04:07:33 -03:00
|
|
|
/**
|
|
|
|
* Handle parameter related messages.
|
|
|
|
*/
|
2012-08-04 19:12:36 -03:00
|
|
|
void mavlink_pm_message_handler(const mavlink_channel_t chan, const mavlink_message_t *msg);
|
2012-08-20 04:07:33 -03:00
|
|
|
|
|
|
|
/**
|
|
|
|
* Send all parameters at once.
|
|
|
|
*
|
|
|
|
* This function blocks until all parameters have been sent.
|
|
|
|
* it delays each parameter by the passed amount of microseconds.
|
|
|
|
*
|
2012-08-20 04:32:42 -03:00
|
|
|
* @param delay The delay in us between sending all parameters.
|
2012-08-20 04:07:33 -03:00
|
|
|
*/
|
|
|
|
void mavlink_pm_send_all_params(unsigned int delay);
|
|
|
|
|
|
|
|
/**
|
|
|
|
* Send one parameter.
|
|
|
|
*
|
2012-08-20 04:32:42 -03:00
|
|
|
* @param param The parameter id to send.
|
|
|
|
* @return zero on success, nonzero on failure.
|
2012-08-20 04:07:33 -03:00
|
|
|
*/
|
|
|
|
int mavlink_pm_send_param(param_t param);
|
|
|
|
|
2012-08-20 04:32:42 -03:00
|
|
|
/**
|
|
|
|
* Send one parameter identified by index.
|
|
|
|
*
|
|
|
|
* @param index The index of the parameter to send.
|
|
|
|
* @return zero on success, nonzero else.
|
|
|
|
*/
|
|
|
|
int mavlink_pm_send_param_for_index(uint16_t index);
|
|
|
|
|
|
|
|
/**
|
|
|
|
* Send one parameter identified by name.
|
|
|
|
*
|
|
|
|
* @param name The index of the parameter to send.
|
|
|
|
* @return zero on success, nonzero else.
|
|
|
|
*/
|
|
|
|
int mavlink_pm_send_param_for_name(const char* name);
|
|
|
|
|
2012-08-20 04:07:33 -03:00
|
|
|
/**
|
|
|
|
* Send a queue of parameters, one parameter per function call.
|
|
|
|
*
|
2012-08-20 04:32:42 -03:00
|
|
|
* @return zero on success, nonzero on failure
|
2012-08-20 04:07:33 -03:00
|
|
|
*/
|
2012-08-20 04:32:42 -03:00
|
|
|
int mavlink_pm_queued_send(void);
|
2012-08-20 04:07:33 -03:00
|
|
|
|
|
|
|
/**
|
|
|
|
* Start sending the parameter queue.
|
|
|
|
*
|
|
|
|
* This function will not directly send parameters, but instead
|
|
|
|
* activate the sending of one parameter on each call of
|
|
|
|
* mavlink_pm_queued_send().
|
2012-08-20 04:32:42 -03:00
|
|
|
* @see mavlink_pm_queued_send()
|
2012-08-20 04:07:33 -03:00
|
|
|
*/
|
2012-08-20 04:32:42 -03:00
|
|
|
void mavlink_pm_start_queued_send(void);
|