Mount: Alexmos formatting fixes

This commit is contained in:
Randy Mackay 2015-06-05 12:09:12 +09:00
parent 7dcd24137e
commit 7a8fe5f4d4
2 changed files with 25 additions and 23 deletions

View File

@ -92,7 +92,8 @@ void AP_Mount_Alexmos::get_angles()
/*
* set_motor will activate motors if true, and disable them if false.
*/
void AP_Mount_Alexmos::set_motor(bool on){
void AP_Mount_Alexmos::set_motor(bool on)
{
if (on) {
uint8_t data[1] = {(uint8_t)1};
send_command(CMD_MOTORS_ON, data, 1);
@ -138,7 +139,8 @@ void AP_Mount_Alexmos::control_axis(const Vector3f& angle, bool target_in_degree
/*
read current profile profile_id and global parameters from the gimbal settings
*/
void AP_Mount_Alexmos::read_params(uint8_t profile_id){
void AP_Mount_Alexmos::read_params(uint8_t profile_id)
{
uint8_t data[1] = {(uint8_t) profile_id};
send_command(CMD_READ_PARAMS, data, 1);
}