mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
HAL_SITL: enable --gimbal option
instantiates a MAVLink gimbal
This commit is contained in:
parent
7f5b206c55
commit
e7abc07898
@ -89,6 +89,9 @@ void SITL_State::_sitl_setup(void)
|
|||||||
_update_compass(0, 0, 0);
|
_update_compass(0, 0, 0);
|
||||||
_update_gps(0, 0, 0, 0, 0, 0, false);
|
_update_gps(0, 0, 0, 0, 0, 0, false);
|
||||||
#endif
|
#endif
|
||||||
|
if (enable_gimbal) {
|
||||||
|
gimbal = new Gimbal(_sitl->state);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (_synthetic_clock_mode) {
|
if (_synthetic_clock_mode) {
|
||||||
@ -312,6 +315,10 @@ void SITL_State::_fdm_input_local(void)
|
|||||||
// get FDM output from the model
|
// get FDM output from the model
|
||||||
sitl_model->fill_fdm(_sitl->state);
|
sitl_model->fill_fdm(_sitl->state);
|
||||||
|
|
||||||
|
if (gimbal != NULL) {
|
||||||
|
gimbal->update();
|
||||||
|
}
|
||||||
|
|
||||||
// update simulation time
|
// update simulation time
|
||||||
hal.scheduler->stop_clock(_sitl->state.timestamp_us);
|
hal.scheduler->stop_clock(_sitl->state.timestamp_us);
|
||||||
|
|
||||||
|
@ -22,7 +22,7 @@
|
|||||||
#include "../AP_OpticalFlow/AP_OpticalFlow.h"
|
#include "../AP_OpticalFlow/AP_OpticalFlow.h"
|
||||||
#include "../AP_Terrain/AP_Terrain.h"
|
#include "../AP_Terrain/AP_Terrain.h"
|
||||||
#include "../SITL/SITL.h"
|
#include "../SITL/SITL.h"
|
||||||
#include "../SITL/SIM_Multicopter.h"
|
#include "../SITL/SIM_Gimbal.h"
|
||||||
|
|
||||||
class HAL_SITL;
|
class HAL_SITL;
|
||||||
|
|
||||||
@ -191,6 +191,10 @@ private:
|
|||||||
// internal SITL model
|
// internal SITL model
|
||||||
Aircraft *sitl_model;
|
Aircraft *sitl_model;
|
||||||
|
|
||||||
|
// simulated gimbal
|
||||||
|
bool enable_gimbal;
|
||||||
|
Gimbal *gimbal;
|
||||||
|
|
||||||
// TCP address to connect uartC to
|
// TCP address to connect uartC to
|
||||||
const char *_client_address;
|
const char *_client_address;
|
||||||
};
|
};
|
||||||
|
@ -41,6 +41,7 @@ void SITL_State::_usage(void)
|
|||||||
"\t--console use console instead of TCP ports\n"
|
"\t--console use console instead of TCP ports\n"
|
||||||
"\t--instance N set instance of SITL (adds 10*instance to all port numbers)\n"
|
"\t--instance N set instance of SITL (adds 10*instance to all port numbers)\n"
|
||||||
"\t--speedup SPEEDUP set simulation speedup\n"
|
"\t--speedup SPEEDUP set simulation speedup\n"
|
||||||
|
"\t--gimbal enable simulated MAVLink gimbal\n"
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -84,7 +85,8 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|||||||
_instance = 0;
|
_instance = 0;
|
||||||
|
|
||||||
enum long_options {
|
enum long_options {
|
||||||
CMDLINE_CLIENT=0
|
CMDLINE_CLIENT=0,
|
||||||
|
CMDLINE_GIMBAL
|
||||||
};
|
};
|
||||||
|
|
||||||
const struct GetOptLong::option options[] = {
|
const struct GetOptLong::option options[] = {
|
||||||
@ -99,6 +101,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|||||||
{"home", true, 0, 'O'},
|
{"home", true, 0, 'O'},
|
||||||
{"model", true, 0, 'M'},
|
{"model", true, 0, 'M'},
|
||||||
{"client", true, 0, CMDLINE_CLIENT},
|
{"client", true, 0, CMDLINE_CLIENT},
|
||||||
|
{"gimbal", false, 0, CMDLINE_GIMBAL},
|
||||||
{0, false, 0, 0}
|
{0, false, 0, 0}
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -145,6 +148,9 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|||||||
case CMDLINE_CLIENT:
|
case CMDLINE_CLIENT:
|
||||||
_client_address = gopt.optarg;
|
_client_address = gopt.optarg;
|
||||||
break;
|
break;
|
||||||
|
case CMDLINE_GIMBAL:
|
||||||
|
enable_gimbal = true;
|
||||||
|
break;
|
||||||
default:
|
default:
|
||||||
_usage();
|
_usage();
|
||||||
exit(1);
|
exit(1);
|
||||||
|
Loading…
Reference in New Issue
Block a user