mirror of https://github.com/ArduPilot/ardupilot
Improve comments, no functional changes
This commit is contained in:
parent
18c8389c26
commit
25916e9a92
|
@ -438,6 +438,7 @@
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// CAMERA TRIGGER AND CONTROL
|
// CAMERA TRIGGER AND CONTROL
|
||||||
//
|
//
|
||||||
|
// uses 1182 bytes of memory
|
||||||
#ifndef CAMERA
|
#ifndef CAMERA
|
||||||
# define CAMERA ENABLED
|
# define CAMERA ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
@ -815,7 +816,7 @@
|
||||||
# define MAVLINK_TELEMETRY_PORT_DELAY 2000
|
# define MAVLINK_TELEMETRY_PORT_DELAY 2000
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// use this to disable gen-fencing
|
// use this to disable geo-fencing
|
||||||
#ifndef GEOFENCE_ENABLED
|
#ifndef GEOFENCE_ENABLED
|
||||||
# define GEOFENCE_ENABLED ENABLED
|
# define GEOFENCE_ENABLED ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -422,14 +422,14 @@ void AP_Mount::status_msg(mavlink_message_t *msg)
|
||||||
case MAV_MOUNT_MODE_NEUTRAL: // neutral position (Roll,Pitch,Yaw) from EEPROM
|
case MAV_MOUNT_MODE_NEUTRAL: // neutral position (Roll,Pitch,Yaw) from EEPROM
|
||||||
case MAV_MOUNT_MODE_MAVLINK_TARGETING: // neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization
|
case MAV_MOUNT_MODE_MAVLINK_TARGETING: // neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization
|
||||||
case MAV_MOUNT_MODE_RC_TARGETING: // neutral position and start RC Roll,Pitch,Yaw control with stabilization
|
case MAV_MOUNT_MODE_RC_TARGETING: // neutral position and start RC Roll,Pitch,Yaw control with stabilization
|
||||||
packet.pointing_b = _roll_angle*100; ///< degrees*100
|
packet.pointing_b = _roll_angle*100; // degrees*100
|
||||||
packet.pointing_a = _tilt_angle*100; ///< degrees*100
|
packet.pointing_a = _tilt_angle*100; // degrees*100
|
||||||
packet.pointing_c = _pan_angle*100; ///< degrees*100
|
packet.pointing_c = _pan_angle*100; // degrees*100
|
||||||
break;
|
break;
|
||||||
case MAV_MOUNT_MODE_GPS_POINT: // neutral position and start to point to Lat,Lon,Alt
|
case MAV_MOUNT_MODE_GPS_POINT: // neutral position and start to point to Lat,Lon,Alt
|
||||||
packet.pointing_a = _target_GPS_location.lat; ///< latitude
|
packet.pointing_a = _target_GPS_location.lat; // latitude
|
||||||
packet.pointing_b = _target_GPS_location.lng; ///< longitude
|
packet.pointing_b = _target_GPS_location.lng; // longitude
|
||||||
packet.pointing_c = _target_GPS_location.alt; ///< altitude
|
packet.pointing_c = _target_GPS_location.alt; // altitude
|
||||||
break;
|
break;
|
||||||
case MAV_MOUNT_MODE_ENUM_END:
|
case MAV_MOUNT_MODE_ENUM_END:
|
||||||
break;
|
break;
|
||||||
|
|
Loading…
Reference in New Issue