mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_SerialManager: added RobotisServo protocol support
This commit is contained in:
parent
aa7221d1bf
commit
28970ed176
@ -66,7 +66,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
|||||||
// @Param: 1_PROTOCOL
|
// @Param: 1_PROTOCOL
|
||||||
// @DisplayName: Telem1 protocol selection
|
// @DisplayName: Telem1 protocol selection
|
||||||
// @Description: Control what protocol to use on the Telem1 port. Note that the Frsky options require external converter hardware. See the wiki for details.
|
// @Description: Control what protocol to use on the Telem1 port. Note that the Frsky options require external converter hardware. See the wiki for details.
|
||||||
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow
|
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, SerialProtocol_MAVLink),
|
AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, SerialProtocol_MAVLink),
|
||||||
@ -81,7 +81,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
|||||||
// @Param: 2_PROTOCOL
|
// @Param: 2_PROTOCOL
|
||||||
// @DisplayName: Telemetry 2 protocol selection
|
// @DisplayName: Telemetry 2 protocol selection
|
||||||
// @Description: Control what protocol to use on the Telem2 port. Note that the Frsky options require external converter hardware. See the wiki for details.
|
// @Description: Control what protocol to use on the Telem2 port. Note that the Frsky options require external converter hardware. See the wiki for details.
|
||||||
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow
|
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("2_PROTOCOL", 3, AP_SerialManager, state[2].protocol, SERIAL2_PROTOCOL_DEFAULT),
|
AP_GROUPINFO("2_PROTOCOL", 3, AP_SerialManager, state[2].protocol, SERIAL2_PROTOCOL_DEFAULT),
|
||||||
@ -96,7 +96,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
|||||||
// @Param: 3_PROTOCOL
|
// @Param: 3_PROTOCOL
|
||||||
// @DisplayName: Serial 3 (GPS) protocol selection
|
// @DisplayName: Serial 3 (GPS) protocol selection
|
||||||
// @Description: Control what protocol Serial 3 (GPS) should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
|
// @Description: Control what protocol Serial 3 (GPS) should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
|
||||||
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow
|
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("3_PROTOCOL", 5, AP_SerialManager, state[3].protocol, SerialProtocol_GPS),
|
AP_GROUPINFO("3_PROTOCOL", 5, AP_SerialManager, state[3].protocol, SerialProtocol_GPS),
|
||||||
@ -111,7 +111,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
|||||||
// @Param: 4_PROTOCOL
|
// @Param: 4_PROTOCOL
|
||||||
// @DisplayName: Serial4 protocol selection
|
// @DisplayName: Serial4 protocol selection
|
||||||
// @Description: Control what protocol Serial4 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
|
// @Description: Control what protocol Serial4 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
|
||||||
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow
|
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("4_PROTOCOL", 7, AP_SerialManager, state[4].protocol, SerialProtocol_GPS),
|
AP_GROUPINFO("4_PROTOCOL", 7, AP_SerialManager, state[4].protocol, SerialProtocol_GPS),
|
||||||
@ -126,7 +126,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
|||||||
// @Param: 5_PROTOCOL
|
// @Param: 5_PROTOCOL
|
||||||
// @DisplayName: Serial5 protocol selection
|
// @DisplayName: Serial5 protocol selection
|
||||||
// @Description: Control what protocol Serial5 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
|
// @Description: Control what protocol Serial5 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
|
||||||
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow
|
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("5_PROTOCOL", 9, AP_SerialManager, state[5].protocol, SERIAL5_PROTOCOL),
|
AP_GROUPINFO("5_PROTOCOL", 9, AP_SerialManager, state[5].protocol, SERIAL5_PROTOCOL),
|
||||||
@ -143,7 +143,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
|||||||
// @Param: 6_PROTOCOL
|
// @Param: 6_PROTOCOL
|
||||||
// @DisplayName: Serial6 protocol selection
|
// @DisplayName: Serial6 protocol selection
|
||||||
// @Description: Control what protocol Serial6 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
|
// @Description: Control what protocol Serial6 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
|
||||||
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow
|
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("6_PROTOCOL", 12, AP_SerialManager, state[6].protocol, SERIAL6_PROTOCOL),
|
AP_GROUPINFO("6_PROTOCOL", 12, AP_SerialManager, state[6].protocol, SERIAL6_PROTOCOL),
|
||||||
@ -331,6 +331,14 @@ void AP_SerialManager::init()
|
|||||||
state[i].uart->begin(map_baudrate(state[i].baud), 30, 30);
|
state[i].uart->begin(map_baudrate(state[i].baud), 30, 30);
|
||||||
state[i].uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
|
state[i].uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case SerialProtocol_Robotis:
|
||||||
|
state[i].uart->begin(map_baudrate(state[i].baud),
|
||||||
|
AP_SERIALMANAGER_ROBOTIS_BUFSIZE_RX,
|
||||||
|
AP_SERIALMANAGER_ROBOTIS_BUFSIZE_TX);
|
||||||
|
state[i].uart->set_unbuffered_writes(true);
|
||||||
|
state[i].uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -68,6 +68,9 @@
|
|||||||
#define AP_SERIALMANAGER_VOLZ_BUFSIZE_RX 128
|
#define AP_SERIALMANAGER_VOLZ_BUFSIZE_RX 128
|
||||||
#define AP_SERIALMANAGER_VOLZ_BUFSIZE_TX 128
|
#define AP_SERIALMANAGER_VOLZ_BUFSIZE_TX 128
|
||||||
|
|
||||||
|
#define AP_SERIALMANAGER_ROBOTIS_BUFSIZE_RX 128
|
||||||
|
#define AP_SERIALMANAGER_ROBOTIS_BUFSIZE_TX 128
|
||||||
|
|
||||||
// SBUS servo outputs
|
// SBUS servo outputs
|
||||||
#define AP_SERIALMANAGER_SBUS1_BAUD 100000
|
#define AP_SERIALMANAGER_SBUS1_BAUD 100000
|
||||||
#define AP_SERIALMANAGER_SBUS1_BUFSIZE_RX 16
|
#define AP_SERIALMANAGER_SBUS1_BUFSIZE_RX 16
|
||||||
@ -102,6 +105,7 @@ public:
|
|||||||
SerialProtocol_ESCTelemetry = 16,
|
SerialProtocol_ESCTelemetry = 16,
|
||||||
SerialProtocol_Devo_Telem = 17,
|
SerialProtocol_Devo_Telem = 17,
|
||||||
SerialProtocol_OpticalFlow = 18,
|
SerialProtocol_OpticalFlow = 18,
|
||||||
|
SerialProtocol_Robotis = 19,
|
||||||
};
|
};
|
||||||
|
|
||||||
// get singleton instance
|
// get singleton instance
|
||||||
|
Loading…
Reference in New Issue
Block a user