Skip to content

Commit

Permalink
Mount: add get_mode and set_mode_to_default methods
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 committed Mar 5, 2014
1 parent 7992a1a commit 1c457d8
Showing 1 changed file with 7 additions and 0 deletions.
7 changes: 7 additions & 0 deletions libraries/AP_Mount/AP_Mount.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,13 @@ class AP_Mount
k_pan_tilt_roll = 3, ///< yaw-pitch-roll
};

// get_mode - return current mount mode
enum MAV_MOUNT_MODE get_mode() const { return (enum MAV_MOUNT_MODE)_mount_mode.get(); }

// set_mode_to_default - restores the mode to it's default held in the MNT_MODE parameter
// this operation requires 2ms on an APM2, 0.7ms on a Pixhawk/PX4
void set_mode_to_default() { _mount_mode.load(); }

// MAVLink methods
void configure_msg(mavlink_message_t* msg);
void control_msg(mavlink_message_t* msg);
Expand Down

0 comments on commit 1c457d8

Please sign in to comment.