AP_Gripper: use new SRV_Channels API

This commit is contained in:
Andrew Tridgell 2017-01-07 12:06:40 +11:00
parent 5817cc400c
commit b3d30cbd4b
4 changed files with 10 additions and 10 deletions

View File

@ -55,7 +55,7 @@ void AP_Gripper_EPM::grab()
#endif
{
// move the servo output to the grab position
RC_Channel_aux::set_radio(RC_Channel_aux::k_gripper, config.grab_pwm);
SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.grab_pwm);
}
}
@ -77,7 +77,7 @@ void AP_Gripper_EPM::release()
#endif
{
// move the servo to the release position
RC_Channel_aux::set_radio(RC_Channel_aux::k_gripper, config.release_pwm);
SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.release_pwm);
}
}
@ -86,7 +86,7 @@ void AP_Gripper_EPM::neutral()
{
if (!should_use_uavcan()) {
// move the servo to the off position
RC_Channel_aux::set_radio(RC_Channel_aux::k_gripper, config.neutral_pwm);
SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.neutral_pwm);
}
}

View File

@ -16,7 +16,7 @@
#include "AP_Gripper.h"
#include "AP_Gripper_Backend.h"
#include <RC_Channel/RC_Channel.h>
#include <SRV_Channel/SRV_Channel.h>
#define EPM_RETURN_TO_NEUTRAL_MS 500 // EPM PWM returns to neutral position this many milliseconds after grab or release

View File

@ -11,22 +11,22 @@ void AP_Gripper_Servo::init_gripper()
void AP_Gripper_Servo::grab()
{
// move the servo to the grab position
RC_Channel_aux::set_radio(RC_Channel_aux::k_gripper, config.grab_pwm);
SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.grab_pwm);
action_timestamp = AP_HAL::millis();
}
void AP_Gripper_Servo::release()
{
// move the servo to the release position
RC_Channel_aux::set_radio(RC_Channel_aux::k_gripper, config.release_pwm);
SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.release_pwm);
action_timestamp = AP_HAL::millis();
}
bool AP_Gripper_Servo::has_state_pwm(const uint16_t pwm) const
{
// return true if servo is in position represented by pwm
int16_t current_pwm;
if (!RC_Channel_aux::get_radio(RC_Channel_aux::k_gripper, current_pwm)) {
uint16_t current_pwm;
if (!SRV_Channels::get_output_pwm(SRV_Channel::k_gripper, current_pwm)) {
// function not assigned to a channel, perhaps?
return false;
}
@ -61,7 +61,7 @@ bool AP_Gripper_Servo::valid() const
if (!AP_Gripper_Backend::valid()) {
return false;
}
if (!RC_Channel_aux::function_assigned(RC_Channel_aux::k_gripper)) {
if (!SRV_Channels::function_assigned(SRV_Channel::k_gripper)) {
return false;
}
return true;

View File

@ -16,7 +16,7 @@
#pragma once
#include <AP_Gripper/AP_Gripper_Backend.h>
#include <RC_Channel/RC_Channel.h>
#include <SRV_Channel/SRV_Channel.h>
class AP_Gripper_Servo : public AP_Gripper_Backend {
public: