uncrustify libraries/AP_Camera/AP_Camera.cpp

This commit is contained in:
uncrustify 2012-08-16 23:09:29 -07:00 committed by Pat Hickey
parent fa90f0b80f
commit 30107b9665
1 changed files with 113 additions and 113 deletions

View File

@ -47,7 +47,7 @@ AP_Camera::throttle_pic()
{
// TODO find a way to do this without using the global parameter g
// g.channel_throttle.radio_out = g.throttle_min;
if (thr_pic == 10){
if (thr_pic == 10) {
servo_pic(); // triggering method
thr_pic = 0;
// g.channel_throttle.radio_out = g.throttle_cruise;
@ -61,7 +61,7 @@ AP_Camera::distance_pic()
{
// TODO find a way to do this without using the global parameter g
// g.channel_throttle.radio_out = g.throttle_min;
if (wp_distance < 3){
if (wp_distance < 3) {
servo_pic(); // triggering method
// g.channel_throttle.radio_out = g.throttle_cruise;
}
@ -106,7 +106,7 @@ AP_Camera::trigger_pic_cleanup()
{
if (keep_cam_trigg_active_cycles)
{
keep_cam_trigg_active_cycles --;
keep_cam_trigg_active_cycles--;
}
else
{
@ -139,15 +139,15 @@ AP_Camera::configure_msg(mavlink_message_t* msg)
}
// TODO do something with these values
/*
packet.aperture
packet.command_id
packet.engine_cut_off
packet.exposure_type
packet.extra_param
packet.extra_value
packet.iso
packet.mode
packet.shutter_speed
* packet.aperture
* packet.command_id
* packet.engine_cut_off
* packet.exposure_type
* packet.extra_param
* packet.extra_value
* packet.iso
* packet.mode
* packet.shutter_speed
*/
// echo the message to the ArduCam OSD camera control board
// for more info see: http://code.google.com/p/arducam-osd/
@ -167,14 +167,14 @@ AP_Camera::control_msg(mavlink_message_t* msg)
}
// TODO do something with these values
/*
packet.command_id
packet.extra_param
packet.extra_value
packet.focus_lock
packet.session
packet.shot
packet.zoom_pos
packet.zoom_step
* packet.command_id
* packet.extra_param
* packet.extra_value
* packet.focus_lock
* packet.session
* packet.shot
* packet.zoom_pos
* packet.zoom_step
*/
if (packet.shot)
{