Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Simulator: Make battery discharging configurable. #7826

Merged
merged 1 commit into from
Aug 20, 2017
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
17 changes: 17 additions & 0 deletions src/modules/simulator/simulator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,6 +122,23 @@ void Simulator::write_airspeed_data(void *buf)
_airspeed.writeData(buf);
}

void Simulator::parameters_update(bool force)
{
bool updated;
struct parameter_update_s param_upd;

orb_check(_param_sub, &updated);

if (updated) {
orb_copy(ORB_ID(parameter_update), _param_sub, &param_upd);
}

if (updated || force) {
// update C++ param system
updateParams();
}
}

int Simulator::start(int argc, char *argv[])
{
int ret = 0;
Expand Down
20 changes: 15 additions & 5 deletions src/modules/simulator/simulator.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,8 @@
#include <drivers/drv_rc_input.h>
#include <systemlib/perf_counter.h>
#include <systemlib/battery.h>
#include <controllib/blocks.hpp>
#include <controllib/block/BlockParam.hpp>
#include <uORB/uORB.h>
#include <uORB/topics/optical_flow.h>
#include <uORB/topics/distance_sensor.h>
Expand Down Expand Up @@ -185,7 +187,7 @@ template <typename RType> class Report

};

class Simulator
class Simulator : public control::SuperBlock
{
public:
static Simulator *getInstance();
Expand Down Expand Up @@ -223,7 +225,7 @@ class Simulator
bool isInitialized() { return _initialized; }

private:
Simulator() :
Simulator() : SuperBlock(nullptr, "SIM"),
_accel(1),
_mpu(1),
_baro(1),
Expand All @@ -247,6 +249,7 @@ class Simulator
_vision_attitude_pub(nullptr),
_dist_pub(nullptr),
_battery_pub(nullptr),
_param_sub(-1),
_initialized(false),
_realtime_factor(1.0),
_system_type(0)
Expand All @@ -270,23 +273,25 @@ class Simulator
_actuators{},
_attitude{},
_manual{},
_vehicle_status{}
_vehicle_status{},
_battery_drain_interval_s(this, "BAT_DRAIN")
#endif
{
// We need to know the type for the correct mapping from
// actuator controls to the hil actuator message.
param_t param_system_type = param_find("MAV_TYPE");
param_get(param_system_type, &_system_type);

for (unsigned i = 0; i < (sizeof(_actuator_outputs_sub) / sizeof(_actuator_outputs_sub[0])); i++)
{
for (unsigned i = 0; i < (sizeof(_actuator_outputs_sub) / sizeof(_actuator_outputs_sub[0])); i++) {
_actuator_outputs_sub[i] = -1;
}

simulator::RawGPSData gps_data{};
gps_data.eph = UINT16_MAX;
gps_data.epv = UINT16_MAX;
_gps.writeData(&gps_data);

_param_sub = orb_subscribe(ORB_ID(parameter_update));
}
~Simulator()
{
Expand Down Expand Up @@ -329,6 +334,8 @@ class Simulator
orb_advert_t _dist_pub;
orb_advert_t _battery_pub;

int _param_sub;

bool _initialized;
double _realtime_factor; ///< How fast the simulation runs in comparison to real system time
hrt_abstime _last_sim_timestamp;
Expand Down Expand Up @@ -374,6 +381,8 @@ class Simulator
struct manual_control_setpoint_s _manual;
struct vehicle_status_s _vehicle_status;

control::BlockParamFloat _battery_drain_interval_s; ///< battery drain interval

void poll_topics();
void handle_message(mavlink_message_t *msg, bool publish);
void send_controls();
Expand All @@ -383,6 +392,7 @@ class Simulator
void send_mavlink_message(const uint8_t msgid, const void *msg, uint8_t component_ID);
void update_sensors(mavlink_hil_sensor_t *imu);
void update_gps(mavlink_hil_gps_t *gps_sim);
void parameters_update(bool force);
static void *sending_trampoline(void *);
void send();
#endif
Expand Down
3 changes: 2 additions & 1 deletion src/modules/simulator/simulator_mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -356,7 +356,7 @@ void Simulator::handle_message(mavlink_message_t *msg, bool publish)
update_sensors(&imu);

// battery simulation
const float discharge_interval_us = 60 * 1000 * 1000;
const float discharge_interval_us = _battery_drain_interval_s.get() * 1000 * 1000;

bool armed = (_vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED);

Expand Down Expand Up @@ -625,6 +625,7 @@ void Simulator::send()

if (fds[0].revents & POLLIN) {
// got new data to read, update all topics
parameters_update(false);
poll_topics();
send_controls();
}
Expand Down
11 changes: 11 additions & 0 deletions src/modules/simulator/simulator_params.c
Original file line number Diff line number Diff line change
Expand Up @@ -46,3 +46,14 @@
* @group SITL
*/
PARAM_DEFINE_INT32(SITL_UDP_PRT, 14560);

/**
* Simulator Battery drain interval
*
* @min 1
* @max 86400
* @increment 1
*
* @group SITL
*/
PARAM_DEFINE_FLOAT(SIM_BAT_DRAIN, 60);