mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Sub: Refactor 'strafe' to 'lateral'
This commit is contained in:
parent
3a942434e7
commit
837f429bf0
@ -158,7 +158,7 @@ private:
|
|||||||
RC_Channel *channel_throttle;
|
RC_Channel *channel_throttle;
|
||||||
RC_Channel *channel_yaw;
|
RC_Channel *channel_yaw;
|
||||||
RC_Channel *channel_forward;
|
RC_Channel *channel_forward;
|
||||||
RC_Channel *channel_strafe;
|
RC_Channel *channel_lateral;
|
||||||
|
|
||||||
// Dataflash
|
// Dataflash
|
||||||
DataFlash_Class DataFlash{FIRMWARE_STRING};
|
DataFlash_Class DataFlash{FIRMWARE_STRING};
|
||||||
|
@ -50,7 +50,7 @@ void Sub::acro_run()
|
|||||||
//control_in is range 0-1000
|
//control_in is range 0-1000
|
||||||
//radio_in is raw pwm value
|
//radio_in is raw pwm value
|
||||||
motors.set_forward(channel_forward->radio_in);
|
motors.set_forward(channel_forward->radio_in);
|
||||||
motors.set_strafe(channel_strafe->radio_in);
|
motors.set_lateral(channel_lateral->radio_in);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -156,5 +156,5 @@ void Sub::althold_run()
|
|||||||
//control_in is range 0-1000
|
//control_in is range 0-1000
|
||||||
//radio_in is raw pwm value
|
//radio_in is raw pwm value
|
||||||
motors.set_forward(channel_forward->radio_in);
|
motors.set_forward(channel_forward->radio_in);
|
||||||
motors.set_strafe(channel_strafe->radio_in);
|
motors.set_lateral(channel_lateral->radio_in);
|
||||||
}
|
}
|
||||||
|
@ -60,5 +60,5 @@ void Sub::stabilize_run()
|
|||||||
//control_in is range -1000-1000
|
//control_in is range -1000-1000
|
||||||
//radio_in is raw pwm value
|
//radio_in is raw pwm value
|
||||||
motors.set_forward(channel_forward->radio_in);
|
motors.set_forward(channel_forward->radio_in);
|
||||||
motors.set_strafe(channel_strafe->radio_in);
|
motors.set_lateral(channel_lateral->radio_in);
|
||||||
}
|
}
|
||||||
|
@ -51,7 +51,7 @@ void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t
|
|||||||
channels[3] = r*rpyScale+rpyCenter; // yaw
|
channels[3] = r*rpyScale+rpyCenter; // yaw
|
||||||
channels[4] = mode; // for testing only
|
channels[4] = mode; // for testing only
|
||||||
channels[5] = x*rpyScale+rpyCenter; // forward for ROV
|
channels[5] = x*rpyScale+rpyCenter; // forward for ROV
|
||||||
channels[6] = y*rpyScale+rpyCenter; // strafe for ROV
|
channels[6] = y*rpyScale+rpyCenter; // lateral for ROV
|
||||||
channels[7] = camTilt; // camera tilt
|
channels[7] = camTilt; // camera tilt
|
||||||
channels[8] = lights1;
|
channels[8] = lights1;
|
||||||
channels[9] = 0;
|
channels[9] = 0;
|
||||||
|
Loading…
Reference in New Issue
Block a user