diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 691c33c238..eb44ec4e05 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -659,7 +659,7 @@ static AP_HAL::AnalogSource* rssi_analog_source; // -------------------------------------- #if MOUNT == ENABLED // current_loc uses the baro/gps soloution for altitude rather than gps only. -static AP_Mount camera_mount(¤t_loc, ahrs, 0); +static AP_Mount camera_mount(ahrs, current_loc); #endif //////////////////////////////////////////////////////////////////////////////// @@ -1018,7 +1018,7 @@ static void update_mount() { #if MOUNT == ENABLED // update camera mount's position - camera_mount.update_mount_position(); + camera_mount.update(); #endif #if CAMERA == ENABLED @@ -1134,10 +1134,6 @@ static void one_hz_loop() // update assigned functions and enable auxiliar servos RC_Channel_aux::enable_aux_servos(); -#if MOUNT == ENABLED - camera_mount.update_mount_type(); -#endif - check_usb_mux(); #if AP_TERRAIN_AVAILABLE diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde index 1164a46126..723a69ffe2 100644 --- a/ArduCopter/commands_logic.pde +++ b/ArduCopter/commands_logic.pde @@ -153,16 +153,6 @@ static bool start_command(const AP_Mission::Mission_Command& cmd) break; #endif -#if MOUNT == ENABLED - case MAV_CMD_DO_MOUNT_CONFIGURE: // Mission command to configure a camera mount |Mount operation mode (see MAV_CONFIGURE_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| - camera_mount.configure_cmd(); - break; - - case MAV_CMD_DO_MOUNT_CONTROL: // Mission command to control a camera mount |pitch(deg*100) or lat, depending on mount mode.| roll(deg*100) or lon depending on mount mode| yaw(deg*100) or alt (in cm) depending on mount mode| Empty| Empty| Empty| Empty| - camera_mount.control_cmd(); - break; -#endif - #if PARACHUTE == ENABLED case MAV_CMD_DO_PARACHUTE: // Mission command to configure or release parachute do_parachute(cmd); diff --git a/ArduCopter/control_auto.pde b/ArduCopter/control_auto.pde index 718efe99bb..54e18f8556 100644 --- a/ArduCopter/control_auto.pde +++ b/ArduCopter/control_auto.pde @@ -590,7 +590,7 @@ static void set_auto_yaw_roi(const Location &roi_location) }else{ #if MOUNT == ENABLED // check if mount type requires us to rotate the quad - if(camera_mount.get_mount_type() != AP_Mount::k_pan_tilt && camera_mount.get_mount_type() != AP_Mount::k_pan_tilt_roll) { + if(!camera_mount.has_pan_control()) { roi_WP = pv_location_to_vector(roi_location); set_auto_yaw_mode(AUTO_YAW_ROI); } diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 2185e701e2..6ec6d24b8f 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -231,6 +231,9 @@ static void init_ardupilot() // initialise inertial nav inertial_nav.init(); + // initialise camera mount + camera_mount.init(); + #ifdef USERHOOK_INIT USERHOOK_INIT #endif