mirror of https://github.com/ArduPilot/ardupilot
AP_Volz_Protocol: include cleanups
This commit is contained in:
parent
546961eff4
commit
7a19719a5e
|
@ -9,6 +9,9 @@
|
||||||
|
|
||||||
#include "AP_Volz_Protocol.h"
|
#include "AP_Volz_Protocol.h"
|
||||||
#if NUM_SERVO_CHANNELS
|
#if NUM_SERVO_CHANNELS
|
||||||
|
|
||||||
|
#include <AP_SerialManager/AP_SerialManager.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
const AP_Param::GroupInfo AP_Volz_Protocol::var_info[] = {
|
const AP_Param::GroupInfo AP_Volz_Protocol::var_info[] = {
|
||||||
|
|
|
@ -34,11 +34,8 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_SerialManager/AP_SerialManager.h>
|
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
|
|
||||||
//#include <GCS_MAVLink/GCS.h>
|
|
||||||
|
|
||||||
#define VOLZ_SCALE_VALUE (uint16_t)(VOLZ_EXTENDED_POSITION_MAX - VOLZ_EXTENDED_POSITION_MIN) // Extended Position Data Format defines 100 as 0x0F80, which results in 1920 steps for +100 deg and 1920 steps for -100 degs meaning if you take movement a scaled between -1 ... 1 and multiply by 1920 you get the travel from center
|
#define VOLZ_SCALE_VALUE (uint16_t)(VOLZ_EXTENDED_POSITION_MAX - VOLZ_EXTENDED_POSITION_MIN) // Extended Position Data Format defines 100 as 0x0F80, which results in 1920 steps for +100 deg and 1920 steps for -100 degs meaning if you take movement a scaled between -1 ... 1 and multiply by 1920 you get the travel from center
|
||||||
#define VOLZ_SET_EXTENDED_POSITION_CMD 0xDC
|
#define VOLZ_SET_EXTENDED_POSITION_CMD 0xDC
|
||||||
#define VOLZ_SET_EXTENDED_POSITION_RSP 0x2C
|
#define VOLZ_SET_EXTENDED_POSITION_RSP 0x2C
|
||||||
|
@ -56,8 +53,7 @@ public:
|
||||||
AP_Volz_Protocol();
|
AP_Volz_Protocol();
|
||||||
|
|
||||||
/* Do not allow copies */
|
/* Do not allow copies */
|
||||||
AP_Volz_Protocol(const AP_Volz_Protocol &other) = delete;
|
CLASS_NO_COPY(AP_Volz_Protocol);
|
||||||
AP_Volz_Protocol &operator=(const AP_Volz_Protocol&) = delete;
|
|
||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue