Skip to content

Commit

Permalink
Apply comments
Browse files Browse the repository at this point in the history
  • Loading branch information
Jaeyoung-Lim authored and vooon committed Sep 26, 2019
1 parent 44fa528 commit 783219d
Showing 1 changed file with 18 additions and 12 deletions.
30 changes: 18 additions & 12 deletions mavros_msgs/srv/MountConfigure.srv
Original file line number Diff line number Diff line change
Expand Up @@ -3,19 +3,25 @@

std_msgs/Header header

uint8 mode # See enum MAV_MOUNT_MODE.
uint8 MAV_MOUNT_MODE_RETRACT = 0
uint8 MAV_MOUNT_MODE_NEUTRAL = 1
uint8 MAV_MOUNT_MODE_MAVLINK_TARGETING = 2
uint8 MAV_MOUNT_MODE_RC_TARGETING = 3
uint8 MAV_MOUNT_MODE_GPS_POINT = 4
uint8 mode # See enum MAV_MOUNT_MODE.
#MAV_MOUNT_MODE
uint8 MODE_RETRACT = 0
uint8 MODE_NEUTRAL = 1
uint8 MODE_MAVLINK_TARGETING = 2
uint8 MODE_RC_TARGETING = 3
uint8 MODE_GPS_POINT = 4

bool stabilize_roll # stabilize roll? (1 = yes, 0 = no)
bool stabilize_pitch # stabilize pitch? (1 = yes, 0 = no)
bool stabilize_yaw # stabilize yaw? (1 = yes, 0 = no)
uint8 roll_input # roll input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)
uint8 pitch_input # pitch input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)
uint8 yaw_input # yaw input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)
bool stabilize_roll # stabilize roll? (1 = yes, 0 = no)
bool stabilize_pitch # stabilize pitch? (1 = yes, 0 = no)
bool stabilize_yaw # stabilize yaw? (1 = yes, 0 = no)
uint8 roll_input # roll input (See enum MOUNT_INPUT)
uint8 pitch_input # pitch input (See enum MOUNT_INPUT)
uint8 yaw_input # yaw input (See enum MOUNT_INPUT)

#MOUNT_INPUT
uint8 INPUT_ANGLE_BODY_FRAME = 0
uint8 INPUT_ANGULAR_RATE = 1
uint8 INPUT_ANGLE_ABSOLUTE_FRAME = 2
---
bool success
# raw result returned by COMMAND_ACK
Expand Down

0 comments on commit 783219d

Please sign in to comment.