mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
SITL: rename simin to rcin for better readability
This commit is contained in:
parent
59c84c637e
commit
e2b939df39
@ -116,7 +116,7 @@ void SITL_State::_sitl_setup(const char *home_str)
|
|||||||
*/
|
*/
|
||||||
void SITL_State::_setup_fdm(void)
|
void SITL_State::_setup_fdm(void)
|
||||||
{
|
{
|
||||||
if (!_sitl_rc_in.bind("0.0.0.0", _simin_port)) {
|
if (!_sitl_rc_in.bind("0.0.0.0", _rcin_port)) {
|
||||||
fprintf(stderr, "SITL: socket bind failed - %s\n", strerror(errno));
|
fprintf(stderr, "SITL: socket bind failed - %s\n", strerror(errno));
|
||||||
exit(1);
|
exit(1);
|
||||||
}
|
}
|
||||||
@ -198,9 +198,9 @@ void SITL_State::wait_clock(uint64_t wait_time_usec)
|
|||||||
|
|
||||||
#ifndef HIL_MODE
|
#ifndef HIL_MODE
|
||||||
/*
|
/*
|
||||||
check for a SITL FDM packet
|
check for a SITL RC input packet
|
||||||
*/
|
*/
|
||||||
void SITL_State::_fdm_input(void)
|
void SITL_State::_check_rc_input(void)
|
||||||
{
|
{
|
||||||
ssize_t size;
|
ssize_t size;
|
||||||
struct pwm_packet {
|
struct pwm_packet {
|
||||||
@ -271,7 +271,7 @@ void SITL_State::_fdm_input_local(void)
|
|||||||
SITL::Aircraft::sitl_input input;
|
SITL::Aircraft::sitl_input input;
|
||||||
|
|
||||||
// check for direct RC input
|
// check for direct RC input
|
||||||
_fdm_input();
|
_check_rc_input();
|
||||||
|
|
||||||
// construct servos structure for FDM
|
// construct servos structure for FDM
|
||||||
_simulator_servos(input);
|
_simulator_servos(input);
|
||||||
|
@ -129,7 +129,7 @@ private:
|
|||||||
double rollRate, double pitchRate,double yawRate, // Local to plane
|
double rollRate, double pitchRate,double yawRate, // Local to plane
|
||||||
double xAccel, double yAccel, double zAccel, // Local to plane
|
double xAccel, double yAccel, double zAccel, // Local to plane
|
||||||
float airspeed, float altitude);
|
float airspeed, float altitude);
|
||||||
void _fdm_input(void);
|
void _check_rc_input(void);
|
||||||
void _fdm_input_local(void);
|
void _fdm_input_local(void);
|
||||||
void _output_to_flightgear(void);
|
void _output_to_flightgear(void);
|
||||||
void _simulator_servos(SITL::Aircraft::sitl_input &input);
|
void _simulator_servos(SITL::Aircraft::sitl_input &input);
|
||||||
@ -163,7 +163,7 @@ private:
|
|||||||
SocketAPM _sitl_rc_in{true};
|
SocketAPM _sitl_rc_in{true};
|
||||||
SITL::SITL *_sitl;
|
SITL::SITL *_sitl;
|
||||||
uint16_t _rcout_port;
|
uint16_t _rcout_port;
|
||||||
uint16_t _simin_port;
|
uint16_t _rcin_port;
|
||||||
float _current;
|
float _current;
|
||||||
|
|
||||||
bool _synthetic_clock_mode;
|
bool _synthetic_clock_mode;
|
||||||
|
@ -129,7 +129,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|||||||
_synthetic_clock_mode = false;
|
_synthetic_clock_mode = false;
|
||||||
_base_port = 5760;
|
_base_port = 5760;
|
||||||
_rcout_port = 5502;
|
_rcout_port = 5502;
|
||||||
_simin_port = 5501;
|
_rcin_port = 5501;
|
||||||
_fdm_address = "127.0.0.1";
|
_fdm_address = "127.0.0.1";
|
||||||
_client_address = nullptr;
|
_client_address = nullptr;
|
||||||
_use_fg_view = false;
|
_use_fg_view = false;
|
||||||
@ -198,7 +198,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|||||||
_instance = atoi(gopt.optarg);
|
_instance = atoi(gopt.optarg);
|
||||||
_base_port += _instance * 10;
|
_base_port += _instance * 10;
|
||||||
_rcout_port += _instance * 10;
|
_rcout_port += _instance * 10;
|
||||||
_simin_port += _instance * 10;
|
_rcin_port += _instance * 10;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 'P':
|
case 'P':
|
||||||
|
Loading…
Reference in New Issue
Block a user