Browse Source

Rename Simulator class private methods names to match snake case of other private class methods.

sbg
mcsauder 6 years ago committed by Beat Küng
parent
commit
1eced05359
  1. 8
      src/modules/simulator/simulator.cpp
  2. 4
      src/modules/simulator/simulator.h
  3. 4
      src/modules/simulator/simulator_mavlink.cpp

8
src/modules/simulator/simulator.cpp

@ -160,18 +160,18 @@ int Simulator::start(int argc, char *argv[]) @@ -160,18 +160,18 @@ int Simulator::start(int argc, char *argv[])
}
if (argv[2][1] == 's') {
_instance->initializeSensorData();
_instance->initialize_sensor_data();
#ifndef __PX4_QURT
// Update sensor data
_instance->pollForMAVLinkMessages(false);
_instance->poll_for_MAVLink_messages(false);
#endif
} else if (argv[2][1] == 'p') {
// Update sensor data
_instance->pollForMAVLinkMessages(true);
_instance->poll_for_MAVLink_messages(true);
} else {
_instance->initializeSensorData();
_instance->initialize_sensor_data();
_instance->_initialized = true;
}

4
src/modules/simulator/simulator.h

@ -272,7 +272,7 @@ private: @@ -272,7 +272,7 @@ private:
}
// class methods
void initializeSensorData();
void initialize_sensor_data();
int publish_sensor_topics(mavlink_hil_sensor_t *imu);
int publish_flow_topic(mavlink_hil_optical_flow_t *flow);
@ -338,7 +338,7 @@ private: @@ -338,7 +338,7 @@ private:
void parameters_update(bool force);
void poll_topics();
void pollForMAVLinkMessages(bool publish);
void poll_for_MAVLink_messages(bool publish);
void request_hil_state_quaternion();
void send();
void send_controls();

4
src/modules/simulator/simulator_mavlink.cpp

@ -632,7 +632,7 @@ void Simulator::send_heartbeat() @@ -632,7 +632,7 @@ void Simulator::send_heartbeat()
send_mavlink_message(message);
}
void Simulator::initializeSensorData()
void Simulator::initialize_sensor_data()
{
// Write sensor data to memory so that drivers can copy data from there.
RawMPUData mpu = {};
@ -664,7 +664,7 @@ void Simulator::initializeSensorData() @@ -664,7 +664,7 @@ void Simulator::initializeSensorData()
write_airspeed_data(&airspeed);
}
void Simulator::pollForMAVLinkMessages(bool publish)
void Simulator::poll_for_MAVLink_messages(bool publish)
{
#ifdef __PX4_DARWIN
pthread_setname_np("sim_rcv");

Loading…
Cancel
Save