Sub: correct compilation when features disabled

Gripper
Mount
This commit is contained in:
Peter Barker 2018-04-20 22:41:04 +10:00 committed by Randy Mackay
parent 3afe591368
commit 0a0e11ba21
7 changed files with 11 additions and 3 deletions

View File

@ -61,7 +61,7 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
SCHED_TASK(accel_cal_update, 10, 100),
SCHED_TASK(terrain_update, 10, 100),
#if GRIPPER_ENABLED == ENABLED
SCHED_TASK_CLASS(AP_Gripper, &g2.gripper, update, 10, 75),
SCHED_TASK_CLASS(AP_Gripper, &sub.g2.gripper, update, 10, 75),
#endif
#ifdef USERHOOK_FASTLOOP
SCHED_TASK(userhook_FastLoop, 100, 75),

View File

@ -837,7 +837,9 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
}
case MAVLINK_MSG_ID_PARAM_VALUE: {
#if MOUNT == ENABLED
sub.camera_mount.handle_param_value(msg);
#endif
break;
}

View File

@ -384,7 +384,6 @@ void Sub::Log_Write_Control_Tuning() {}
void Sub::Log_Write_Performance() {}
void Sub::Log_Write_Attitude(void) {}
void Sub::Log_Write_MotBatt() {}
void Sub::Log_Write_Startup() {}
void Sub::Log_Write_Event(uint8_t id) {}
void Sub::Log_Write_Data(uint8_t id, int32_t value) {}
void Sub::Log_Write_Data(uint8_t id, uint32_t value) {}
@ -395,6 +394,7 @@ void Sub::Log_Write_Error(uint8_t sub_system, uint8_t error_code) {}
void Sub::Log_Write_Home_And_Origin() {}
void Sub::Log_Sensor_Health() {}
void Sub::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target) {}
void Sub::Log_Write_Vehicle_Startup_Messages() {}
#if OPTFLOW == ENABLED
void Sub::Log_Write_Optflow() {}

View File

@ -2,6 +2,8 @@
#include <AP_Common/AP_Common.h>
#include <AP_Gripper/AP_Gripper.h>
// Global parameter class.
//
class Parameters {

View File

@ -423,7 +423,7 @@ private:
#endif
#if AVOIDANCE_ENABLED == ENABLED
AC_Avoid avoid{ahrs, inertial_nav, fence, g2.proximity, &g2.beacon};
AC_Avoid avoid{ahrs, fence, g2.proximity, &g2.beacon};
#endif
// Rally library

View File

@ -168,9 +168,11 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
break;
case JSButton::button_function_t::k_mount_center:
#if MOUNT == ENABLED
camera_mount.set_angle_targets(0, 0, 0);
// for some reason the call to set_angle_targets changes the mode to mavlink targeting!
camera_mount.set_mode(MAV_MOUNT_MODE_RC_TARGETING);
#endif
break;
case JSButton::button_function_t::k_mount_tilt_up:
cam_tilt = 1900;

View File

@ -187,8 +187,10 @@ void Sub::init_ardupilot()
mission.init();
// initialise DataFlash library
#if LOGGING_ENABLED == ENABLED
DataFlash.set_mission(&mission);
DataFlash.setVehicle_Startup_Log_Writer(FUNCTOR_BIND(&sub, &Sub::Log_Write_Vehicle_Startup_Messages, void));
#endif
startup_INS_ground();