radio.cpp 2.3 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364
  1. #include "Sub.h"
  2. void Sub::init_rc_in()
  3. {
  4. channel_pitch = RC_Channels::rc_channel(0);
  5. channel_roll = RC_Channels::rc_channel(1);
  6. channel_throttle = RC_Channels::rc_channel(2);
  7. channel_yaw = RC_Channels::rc_channel(3);
  8. channel_forward = RC_Channels::rc_channel(4);
  9. channel_lateral = RC_Channels::rc_channel(5);
  10. // set rc channel ranges
  11. channel_roll->set_angle(ROLL_PITCH_INPUT_MAX);
  12. channel_pitch->set_angle(ROLL_PITCH_INPUT_MAX);
  13. channel_yaw->set_angle(ROLL_PITCH_INPUT_MAX);
  14. channel_throttle->set_range(1000);
  15. channel_forward->set_angle(ROLL_PITCH_INPUT_MAX);
  16. channel_lateral->set_angle(ROLL_PITCH_INPUT_MAX);
  17. // set default dead zones
  18. channel_roll->set_default_dead_zone(30);
  19. channel_pitch->set_default_dead_zone(30);
  20. channel_throttle->set_default_dead_zone(30);
  21. channel_yaw->set_default_dead_zone(40);
  22. channel_forward->set_default_dead_zone(30);
  23. channel_lateral->set_default_dead_zone(30);
  24. #if CONFIG_HAL_BOARD != HAL_BOARD_SITL
  25. // initialize rc input to 1500 on control channels (rather than 0)
  26. for (int i = 0; i < 6; i++) {
  27. RC_Channels::set_override(i, 1500);
  28. }
  29. RC_Channels::set_override(6, 1500); // camera pan channel
  30. RC_Channels::set_override(7, 1500); // camera tilt channel
  31. //RC_Channel* chan = RC_Channels::rc_channel(8);
  32. uint16_t min =0;// chan->get_radio_min();
  33. RC_Channels::set_override(8, min); // lights 1 channel
  34. //chan = RC_Channels::rc_channel(9);
  35. //min = chan->get_radio_min();
  36. RC_Channels::set_override(9, min); // lights 2 channel
  37. RC_Channels::set_override(10, 1100); // video switch
  38. #endif
  39. }
  40. // init_rc_out -- initialise motors and check if pilot wants to perform ESC calibration
  41. void Sub::init_rc_out()
  42. {
  43. motors.set_update_rate(g.rc_speed);
  44. motors.set_loop_rate(scheduler.get_loop_rate_hz());
  45. motors.init((AP_Motors::motor_frame_class)g.frame_configuration.get(), AP_Motors::motor_frame_type::MOTOR_FRAME_TYPE_PLUS);
  46. motors.set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
  47. // enable output to motors
  48. if (arming.rc_calibration_checks(true)) {
  49. enable_motor_output();
  50. }
  51. // refresh auxiliary channel to function map
  52. SRV_Channels::update_aux_servo_function();
  53. }