AP_HAL_SITL: add slave JSON instances
This commit is contained in:
parent
8ee38a7171
commit
5ff0f42372
@ -613,6 +613,9 @@ void SITL_State::_fdm_input_local(void)
|
|||||||
// construct servos structure for FDM
|
// construct servos structure for FDM
|
||||||
_simulator_servos(input);
|
_simulator_servos(input);
|
||||||
|
|
||||||
|
// read servo inputs from ride along flight controllers
|
||||||
|
ride_along.receive(input);
|
||||||
|
|
||||||
// update the model
|
// update the model
|
||||||
sitl_model->update_model(input);
|
sitl_model->update_model(input);
|
||||||
|
|
||||||
@ -628,6 +631,9 @@ void SITL_State::_fdm_input_local(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// output JSON state to ride along flight controllers
|
||||||
|
ride_along.send(_sitl->state,sitl_model->get_position_relhome());
|
||||||
|
|
||||||
if (gimbal != nullptr) {
|
if (gimbal != nullptr) {
|
||||||
gimbal->update();
|
gimbal->update();
|
||||||
}
|
}
|
||||||
|
@ -309,6 +309,9 @@ private:
|
|||||||
// simulated VectorNav system:
|
// simulated VectorNav system:
|
||||||
SITL::VectorNav *vectornav;
|
SITL::VectorNav *vectornav;
|
||||||
|
|
||||||
|
// Ride along instances via JSON SITL backend
|
||||||
|
SITL::JSON_Master ride_along;
|
||||||
|
|
||||||
// output socket for flightgear viewing
|
// output socket for flightgear viewing
|
||||||
SocketAPM fg_socket{true};
|
SocketAPM fg_socket{true};
|
||||||
|
|
||||||
|
@ -113,6 +113,7 @@ void SITL_State::_usage(void)
|
|||||||
"\t--irlock-port PORT set port num for irlock\n"
|
"\t--irlock-port PORT set port num for irlock\n"
|
||||||
"\t--start-time TIMESTR set simulation start time in UNIX timestamp\n"
|
"\t--start-time TIMESTR set simulation start time in UNIX timestamp\n"
|
||||||
"\t--sysid ID set SYSID_THISMAV\n"
|
"\t--sysid ID set SYSID_THISMAV\n"
|
||||||
|
"\t--slave number set the number of JSON slaves\n"
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -260,6 +261,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|||||||
CMDLINE_IRLOCK_PORT,
|
CMDLINE_IRLOCK_PORT,
|
||||||
CMDLINE_START_TIME,
|
CMDLINE_START_TIME,
|
||||||
CMDLINE_SYSID,
|
CMDLINE_SYSID,
|
||||||
|
CMDLINE_SLAVE,
|
||||||
};
|
};
|
||||||
|
|
||||||
const struct GetOptLong::option options[] = {
|
const struct GetOptLong::option options[] = {
|
||||||
@ -307,6 +309,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|||||||
{"irlock-port", true, 0, CMDLINE_IRLOCK_PORT},
|
{"irlock-port", true, 0, CMDLINE_IRLOCK_PORT},
|
||||||
{"start-time", true, 0, CMDLINE_START_TIME},
|
{"start-time", true, 0, CMDLINE_START_TIME},
|
||||||
{"sysid", true, 0, CMDLINE_SYSID},
|
{"sysid", true, 0, CMDLINE_SYSID},
|
||||||
|
{"slave", true, 0, CMDLINE_SLAVE},
|
||||||
{0, false, 0, 0}
|
{0, false, 0, 0}
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -462,6 +465,13 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|||||||
case 'h':
|
case 'h':
|
||||||
_usage();
|
_usage();
|
||||||
exit(0);
|
exit(0);
|
||||||
|
case CMDLINE_SLAVE: {
|
||||||
|
const int32_t slaves = atoi(gopt.optarg);
|
||||||
|
if (slaves > 0) {
|
||||||
|
ride_along.init(slaves);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
default:
|
default:
|
||||||
_usage();
|
_usage();
|
||||||
exit(1);
|
exit(1);
|
||||||
|
Loading…
Reference in New Issue
Block a user