Browse Source

Mount_Servo: add set_mode

mission-4.1.18
Randy Mackay 10 years ago committed by Andrew Tridgell
parent
commit
cb5a122dab
  1. 7
      libraries/AP_Mount/AP_Mount_Servo.cpp
  2. 3
      libraries/AP_Mount/AP_Mount_Servo.h

7
libraries/AP_Mount/AP_Mount_Servo.cpp

@ -116,6 +116,13 @@ void AP_Mount_Servo::update() @@ -116,6 +116,13 @@ void AP_Mount_Servo::update()
move_servo(_pan_idx, _angle_bf_output_deg.z*10, _frontend.state[_instance]._pan_angle_min*0.1f, _frontend.state[_instance]._pan_angle_max*0.1f);
}
// set_mode - sets mount's mode
void AP_Mount_Servo::set_mode(enum MAV_MOUNT_MODE mode)
{
// record the mode change and return success
_frontend.state[_instance]._mode = mode;
}
// set_roi_target - sets target location that mount should attempt to point towards
void AP_Mount_Servo::set_roi_target(const struct Location &target_loc)
{

3
libraries/AP_Mount/AP_Mount_Servo.h

@ -41,6 +41,9 @@ public: @@ -41,6 +41,9 @@ public:
// has_pan_control - returns true if this mount can control it's pan (required for multicopters)
virtual bool has_pan_control() const { return _flags.pan_control; }
// set_mode - sets mount's mode
virtual void set_mode(enum MAV_MOUNT_MODE mode);
// set_roi_target - sets target location that mount should attempt to point towards
virtual void set_roi_target(const struct Location &target_loc);

Loading…
Cancel
Save