Copter: optionalize the winch

This commit is contained in:
murata 2018-02-10 23:23:06 +09:00 committed by Randy Mackay
parent ec98cab262
commit c31c2a4cf1
11 changed files with 35 additions and 2 deletions

View File

@ -153,7 +153,9 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
#if GRIPPER_ENABLED == ENABLED #if GRIPPER_ENABLED == ENABLED
SCHED_TASK_CLASS(AP_Gripper, &copter.g2.gripper, update, 10, 75), SCHED_TASK_CLASS(AP_Gripper, &copter.g2.gripper, update, 10, 75),
#endif #endif
#if WINCH_ENABLED == ENABLED
SCHED_TASK(winch_update, 10, 50), SCHED_TASK(winch_update, 10, 50),
#endif
#ifdef USERHOOK_FASTLOOP #ifdef USERHOOK_FASTLOOP
SCHED_TASK(userhook_FastLoop, 100, 75), SCHED_TASK(userhook_FastLoop, 100, 75),
#endif #endif

View File

@ -95,8 +95,6 @@
#include <AP_Arming/AP_Arming.h> #include <AP_Arming/AP_Arming.h>
#include <AP_VisualOdom/AP_VisualOdom.h> #include <AP_VisualOdom/AP_VisualOdom.h>
#include <AP_SmartRTL/AP_SmartRTL.h> #include <AP_SmartRTL/AP_SmartRTL.h>
#include <AP_WheelEncoder/AP_WheelEncoder.h>
#include <AP_Winch/AP_Winch.h>
#include <AP_TempCalibration/AP_TempCalibration.h> #include <AP_TempCalibration/AP_TempCalibration.h>
// Configuration // Configuration
@ -134,6 +132,11 @@
#include "toy_mode.h" #include "toy_mode.h"
#endif #endif
#if WINCH_ENABLED == ENABLED
#include <AP_WheelEncoder/AP_WheelEncoder.h>
#include <AP_Winch/AP_Winch.h>
#endif
// Local modules // Local modules
#include "Parameters.h" #include "Parameters.h"
#include "avoidance_adsb.h" #include "avoidance_adsb.h"

View File

@ -1212,6 +1212,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
break; break;
#endif #endif
#if WINCH_ENABLED == ENABLED
case MAV_CMD_DO_WINCH: case MAV_CMD_DO_WINCH:
// param1 : winch number (ignored) // param1 : winch number (ignored)
// param2 : action (0=relax, 1=relative length control, 2=rate control). See WINCH_ACTIONS enum. // param2 : action (0=relax, 1=relative length control, 2=rate control). See WINCH_ACTIONS enum.
@ -1244,6 +1245,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
} }
} }
break; break;
#endif
/* Solo user presses Fly button */ /* Solo user presses Fly button */
case MAV_CMD_SOLO_BTN_FLY_CLICK: { case MAV_CMD_SOLO_BTN_FLY_CLICK: {

View File

@ -944,6 +944,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Path: ../libraries/AP_SmartRTL/AP_SmartRTL.cpp // @Path: ../libraries/AP_SmartRTL/AP_SmartRTL.cpp
AP_SUBGROUPINFO(smart_rtl, "SRTL_", 21, ParametersG2, AP_SmartRTL), AP_SUBGROUPINFO(smart_rtl, "SRTL_", 21, ParametersG2, AP_SmartRTL),
#if WINCH_ENABLED == ENABLED
// @Group: WENC // @Group: WENC
// @Path: ../libraries/AP_WheelEncoder/AP_WheelEncoder.cpp // @Path: ../libraries/AP_WheelEncoder/AP_WheelEncoder.cpp
AP_SUBGROUPINFO(wheel_encoder, "WENC", 22, ParametersG2, AP_WheelEncoder), AP_SUBGROUPINFO(wheel_encoder, "WENC", 22, ParametersG2, AP_WheelEncoder),
@ -951,6 +952,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Group: WINCH_ // @Group: WINCH_
// @Path: ../libraries/AP_Winch/AP_Winch.cpp // @Path: ../libraries/AP_Winch/AP_Winch.cpp
AP_SUBGROUPINFO(winch, "WINCH", 23, ParametersG2, AP_Winch), AP_SUBGROUPINFO(winch, "WINCH", 23, ParametersG2, AP_Winch),
#endif
// @Param: PILOT_SPEED_DN // @Param: PILOT_SPEED_DN
// @DisplayName: Pilot maximum vertical speed descending // @DisplayName: Pilot maximum vertical speed descending

View File

@ -553,8 +553,10 @@ public:
AP_SmartRTL smart_rtl; AP_SmartRTL smart_rtl;
// wheel encoder and winch // wheel encoder and winch
#if WINCH_ENABLED == ENABLED
AP_WheelEncoder wheel_encoder; AP_WheelEncoder wheel_encoder;
AP_Winch winch; AP_Winch winch;
#endif
// Additional pilot velocity items // Additional pilot velocity items
AP_Int16 pilot_speed_dn; AP_Int16 pilot_speed_dn;

View File

@ -160,9 +160,11 @@ bool Copter::ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
break; break;
#endif #endif
#if WINCH_ENABLED == ENABLED
case MAV_CMD_DO_WINCH: // Mission command to control winch case MAV_CMD_DO_WINCH: // Mission command to control winch
do_winch(cmd); do_winch(cmd);
break; break;
#endif
default: default:
// do nothing with unrecognized MAVLink messages // do nothing with unrecognized MAVLink messages
@ -664,6 +666,7 @@ void Copter::ModeAuto::do_guided_limits(const AP_Mission::Mission_Command& cmd)
} }
#endif #endif
#if WINCH_ENABLED == ENABLED
// control winch based on mission command // control winch based on mission command
void Copter::ModeAuto::do_winch(const AP_Mission::Mission_Command& cmd) void Copter::ModeAuto::do_winch(const AP_Mission::Mission_Command& cmd)
{ {
@ -686,6 +689,7 @@ void Copter::ModeAuto::do_winch(const AP_Mission::Mission_Command& cmd)
break; break;
} }
} }
#endif
/********************************************************************************/ /********************************************************************************/
// Verify Nav (Must) commands // Verify Nav (Must) commands

View File

@ -243,6 +243,12 @@
# define GRIPPER_ENABLED ENABLED # define GRIPPER_ENABLED ENABLED
#endif #endif
//////////////////////////////////////////////////////////////////////////////
// Winch support
#ifndef WINCH_ENABLED
# define WINCH_ENABLED ENABLED
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// Parachute release // Parachute release
#ifndef PARACHUTE #ifndef PARACHUTE

View File

@ -269,7 +269,9 @@ private:
#if GRIPPER_ENABLED == ENABLED #if GRIPPER_ENABLED == ENABLED
void do_gripper(const AP_Mission::Mission_Command& cmd); void do_gripper(const AP_Mission::Mission_Command& cmd);
#endif #endif
#if WINCH_ENABLED == ENABLED
void do_winch(const AP_Mission::Mission_Command& cmd); void do_winch(const AP_Mission::Mission_Command& cmd);
#endif
void do_payload_place(const AP_Mission::Mission_Command& cmd); void do_payload_place(const AP_Mission::Mission_Command& cmd);
void do_RTL(void); void do_RTL(void);

View File

@ -507,13 +507,17 @@ void Copter::update_visual_odom()
// winch and wheel encoder initialisation // winch and wheel encoder initialisation
void Copter::winch_init() void Copter::winch_init()
{ {
#if WINCH_ENABLED == ENABLED
g2.wheel_encoder.init(); g2.wheel_encoder.init();
g2.winch.init(&g2.wheel_encoder); g2.winch.init(&g2.wheel_encoder);
#endif
} }
// winch and wheel encoder update // winch and wheel encoder update
void Copter::winch_update() void Copter::winch_update()
{ {
#if WINCH_ENABLED == ENABLED
g2.wheel_encoder.update(); g2.wheel_encoder.update();
g2.winch.update(); g2.winch.update();
#endif
} }

View File

@ -633,6 +633,7 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
break; break;
case AUXSW_WINCH_ENABLE: case AUXSW_WINCH_ENABLE:
#if WINCH_ENABLED == ENABLED
switch (ch_flag) { switch (ch_flag) {
case AUX_SWITCH_HIGH: case AUX_SWITCH_HIGH:
// high switch maintains current position // high switch maintains current position
@ -645,9 +646,11 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
Log_Write_Event(DATA_WINCH_RELAXED); Log_Write_Event(DATA_WINCH_RELAXED);
break; break;
} }
#endif
break; break;
case AUXSW_WINCH_CONTROL: case AUXSW_WINCH_CONTROL:
#if WINCH_ENABLED == ENABLED
switch (ch_flag) { switch (ch_flag) {
case AUX_SWITCH_LOW: case AUX_SWITCH_LOW:
// raise winch at maximum speed // raise winch at maximum speed
@ -662,6 +665,7 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
g2.winch.set_desired_rate(0.0f); g2.winch.set_desired_rate(0.0f);
break; break;
} }
#endif
break; break;
case AUXSW_RC_OVERRIDE_ENABLE: case AUXSW_RC_OVERRIDE_ENABLE:

View File

@ -213,6 +213,7 @@ void Copter::tuning() {
attitude_control->get_rate_yaw_pid().filt_hz(tuning_value); attitude_control->get_rate_yaw_pid().filt_hz(tuning_value);
break; break;
#if WINCH_ENABLED == ENABLED
case TUNING_WINCH: { case TUNING_WINCH: {
float desired_rate = 0.0f; float desired_rate = 0.0f;
if (v > 0.6f) { if (v > 0.6f) {
@ -224,5 +225,6 @@ void Copter::tuning() {
g2.winch.set_desired_rate(desired_rate); g2.winch.set_desired_rate(desired_rate);
break; break;
} }
#endif
} }
} }