AP_Mount: Remove unneeded headers
This commit is contained in:
parent
8cafbe394f
commit
2d161e3594
@ -21,12 +21,9 @@
|
||||
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_GPS/AP_GPS.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_Common/Location.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
|
||||
// maximum number of mounts
|
||||
#define AP_MOUNT_MAX_INSTANCES 1
|
||||
|
@ -1,4 +1,5 @@
|
||||
#include "AP_Mount_Backend.h"
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
@ -124,16 +125,10 @@ void AP_Mount_Backend::update_targets_from_rc()
|
||||
}
|
||||
}
|
||||
|
||||
// returns the angle (degrees*100) that the RC_Channel input is receiving
|
||||
int32_t AP_Mount_Backend::angle_input(const RC_Channel* rc, int16_t angle_min, int16_t angle_max)
|
||||
{
|
||||
return (rc->norm_input() + 1.0f) * 0.5f * (angle_max - angle_min) + angle_min;
|
||||
}
|
||||
|
||||
// returns the angle (radians) that the RC_Channel input is receiving
|
||||
float AP_Mount_Backend::angle_input_rad(const RC_Channel* rc, int16_t angle_min, int16_t angle_max)
|
||||
{
|
||||
return radians(angle_input(rc, angle_min, angle_max)*0.01f);
|
||||
return radians(((rc->norm_input() + 1.0f) * 0.5f * (angle_max - angle_min) + angle_min)*0.01f);
|
||||
}
|
||||
|
||||
// calc_angle_to_location - calculates the earth-frame roll, tilt and pan angles (and radians) to point at the given target
|
||||
|
@ -21,6 +21,7 @@
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include "AP_Mount.h"
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
|
||||
class AP_Mount_Backend
|
||||
{
|
||||
@ -82,8 +83,7 @@ protected:
|
||||
// update_targets_from_rc - updates angle targets (i.e. _angle_ef_target_rad) using input from receiver
|
||||
void update_targets_from_rc();
|
||||
|
||||
// angle_input, angle_input_rad - convert RC input into an earth-frame target angle
|
||||
int32_t angle_input(const RC_Channel* rc, int16_t angle_min, int16_t angle_max);
|
||||
// angle_input_rad - convert RC input into an earth-frame target angle
|
||||
float angle_input_rad(const RC_Channel* rc, int16_t angle_min, int16_t angle_max);
|
||||
|
||||
// calc_angle_to_location - calculates the earth-frame roll, tilt and pan angles (and radians) to point at the given target
|
||||
|
Loading…
Reference in New Issue
Block a user