forked from Archive/PX4-Autopilot
mavlink: stream rename GROUND_TRUTH -> HIL_STATE_QUATERNION
This commit is contained in:
parent
cb4d974977
commit
5fa1e8e8ba
|
@ -722,10 +722,10 @@ Mavlink::set_hil_enabled(bool hil_enabled)
|
||||||
ret = configure_stream("HIL_ACTUATOR_CONTROLS", 200.0f);
|
ret = configure_stream("HIL_ACTUATOR_CONTROLS", 200.0f);
|
||||||
|
|
||||||
if (_param_sys_hitl.get() == 2) { // Simulation in Hardware enabled ?
|
if (_param_sys_hitl.get() == 2) { // Simulation in Hardware enabled ?
|
||||||
configure_stream("GROUND_TRUTH", 25.0f); // HIL_STATE_QUATERNION to display the SIH
|
configure_stream("HIL_STATE_QUATERNION", 25.0f); // ground truth to display the SIH
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
configure_stream("GROUND_TRUTH", 0.0f);
|
configure_stream("HIL_STATE_QUATERNION", 0.0f);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -734,7 +734,7 @@ Mavlink::set_hil_enabled(bool hil_enabled)
|
||||||
_hil_enabled = false;
|
_hil_enabled = false;
|
||||||
ret = configure_stream("HIL_ACTUATOR_CONTROLS", 0.0f);
|
ret = configure_stream("HIL_ACTUATOR_CONTROLS", 0.0f);
|
||||||
|
|
||||||
configure_stream("GROUND_TRUTH", 0.0f);
|
configure_stream("HIL_STATE_QUATERNION", 0.0f);
|
||||||
}
|
}
|
||||||
|
|
||||||
return ret;
|
return ret;
|
||||||
|
|
|
@ -118,8 +118,8 @@ using matrix::wrap_2pi;
|
||||||
#include "streams/ESC_STATUS.hpp"
|
#include "streams/ESC_STATUS.hpp"
|
||||||
#include "streams/EXTENDED_SYS_STATE.hpp"
|
#include "streams/EXTENDED_SYS_STATE.hpp"
|
||||||
#include "streams/FLIGHT_INFORMATION.hpp"
|
#include "streams/FLIGHT_INFORMATION.hpp"
|
||||||
#include "streams/GROUND_TRUTH.hpp"
|
|
||||||
#include "streams/HIGH_LATENCY2.hpp"
|
#include "streams/HIGH_LATENCY2.hpp"
|
||||||
|
#include "streams/HIL_STATE_QUATERNION.hpp"
|
||||||
#include "streams/OBSTACLE_DISTANCE.hpp"
|
#include "streams/OBSTACLE_DISTANCE.hpp"
|
||||||
#include "streams/ORBIT_EXECUTION_STATUS.hpp"
|
#include "streams/ORBIT_EXECUTION_STATUS.hpp"
|
||||||
#include "streams/PING.hpp"
|
#include "streams/PING.hpp"
|
||||||
|
@ -4994,9 +4994,9 @@ static const StreamListItem streams_list[] = {
|
||||||
#if defined(HIGH_LATENCY2_HPP)
|
#if defined(HIGH_LATENCY2_HPP)
|
||||||
create_stream_list_item<MavlinkStreamHighLatency2>(),
|
create_stream_list_item<MavlinkStreamHighLatency2>(),
|
||||||
#endif // HIGH_LATENCY2_HPP
|
#endif // HIGH_LATENCY2_HPP
|
||||||
#if defined(GROUND_TRUTH_HPP)
|
#if defined(HIL_STATE_QUATERNION_HPP)
|
||||||
create_stream_list_item<MavlinkStreamGroundTruth>(),
|
create_stream_list_item<MavlinkStreamHILStateQuaternion>(),
|
||||||
#endif // GROUND_TRUTH_HPP
|
#endif // HIL_STATE_QUATERNION_HPP
|
||||||
#if defined(PING_HPP)
|
#if defined(PING_HPP)
|
||||||
create_stream_list_item<MavlinkStreamPing>(),
|
create_stream_list_item<MavlinkStreamPing>(),
|
||||||
#endif // PING_HPP
|
#endif // PING_HPP
|
||||||
|
|
|
@ -31,15 +31,15 @@
|
||||||
*
|
*
|
||||||
****************************************************************************/
|
****************************************************************************/
|
||||||
|
|
||||||
#ifndef GROUND_TRUTH_HPP
|
#ifndef HIL_STATE_QUATERNION_HPP
|
||||||
#define GROUND_TRUTH_HPP
|
#define HIL_STATE_QUATERNION_HPP
|
||||||
|
|
||||||
class MavlinkStreamGroundTruth : public MavlinkStream
|
class MavlinkStreamHILStateQuaternion : public MavlinkStream
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamGroundTruth(mavlink); }
|
static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamHILStateQuaternion(mavlink); }
|
||||||
|
|
||||||
static constexpr const char *get_name_static() { return "GROUND_TRUTH"; }
|
static constexpr const char *get_name_static() { return "HIL_STATE_QUATERNION"; }
|
||||||
static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_HIL_STATE_QUATERNION; }
|
static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_HIL_STATE_QUATERNION; }
|
||||||
|
|
||||||
const char *get_name() const override { return get_name_static(); }
|
const char *get_name() const override { return get_name_static(); }
|
||||||
|
@ -55,7 +55,7 @@ public:
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
explicit MavlinkStreamGroundTruth(Mavlink *mavlink) : MavlinkStream(mavlink) {}
|
explicit MavlinkStreamHILStateQuaternion(Mavlink *mavlink) : MavlinkStream(mavlink) {}
|
||||||
|
|
||||||
uORB::Subscription _angular_velocity_sub{ORB_ID(vehicle_angular_velocity_groundtruth)};
|
uORB::Subscription _angular_velocity_sub{ORB_ID(vehicle_angular_velocity_groundtruth)};
|
||||||
uORB::Subscription _att_sub{ORB_ID(vehicle_attitude_groundtruth)};
|
uORB::Subscription _att_sub{ORB_ID(vehicle_attitude_groundtruth)};
|
||||||
|
@ -111,4 +111,4 @@ private:
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // GROUND_TRUTH_HPP
|
#endif // HIL_STATE_QUATERNION_HPP
|
Loading…
Reference in New Issue