Skip to content

Commit

Permalink
remove udral gnss topics
Browse files Browse the repository at this point in the history
  • Loading branch information
PonomarevDA committed May 2, 2024
1 parent 0ed6fdc commit c4e1f1e
Show file tree
Hide file tree
Showing 4 changed files with 1 addition and 45 deletions.
24 changes: 0 additions & 24 deletions src/autopilot_interface/cyphal_hitl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -104,25 +104,6 @@ void CyphalHitlInterface::publish_gnss(const Vector3& global_pose, const Vector3
gps_gnss.msg.horizontal_accuracy = 1.0f / time_multiplier / random_multiplier;
gps_gnss.msg.vertical_accuracy = 1.0f / time_multiplier / random_multiplier;
gps_gnss.publish();

reg_udral_physics_kinematics_geodetic_PointStateVarTs_0_1 gps_point_msg;
gps_point_msg.value.position.value.latitude = global_pose[0] * RAD_TO_DEGREE;
gps_point_msg.value.position.value.longitude = global_pose[1] * RAD_TO_DEGREE;
gps_point_msg.value.position.value.altitude.meter = global_pose[2];

gps_point_msg.value.velocity.value.meter_per_second[0] = ned_velocity[0] * _time_factor;
gps_point_msg.value.velocity.value.meter_per_second[1] = ned_velocity[1] * _time_factor;
gps_point_msg.value.velocity.value.meter_per_second[2] = ned_velocity[2] * _time_factor;
gps_point.publish(gps_point_msg);

gps_sats.msg.value = 10 * time_multiplier * random_multiplier;
gps_sats.publish();

gps_status.msg.value = 3;
gps_status.publish();

gps_pdop.msg.value = 1;
gps_pdop.publish();
}

void CyphalHitlInterface::publish_esc_feedback(uint8_t esc_idx, float voltage, float current, uint32_t rpm) {
Expand Down Expand Up @@ -208,11 +189,6 @@ void CyphalHitlInterface::_update_port_identifiers() {
esc_feedback_3.setPortId(paramsGetIntegerValue(PARAM_ESC_FEEDBACK_3_ID));

gps_gnss.setPortId(paramsGetIntegerValue(PARAM_DS015_GPS_GNSS_ID));
gps_point.setPortId(paramsGetIntegerValue(PARAM_GPS_POINT_ID));
gps_sats.setPortId(paramsGetIntegerValue(PARAM_GPS_SATS_ID));
gps_status.setPortId(paramsGetIntegerValue(PARAM_GPS_STATUS_ID));
gps_pdop.setPortId(paramsGetIntegerValue(PARAM_GPS_PDOP_ID));

baro_pressure.setPortId(paramsGetIntegerValue(BAROMETER_PRESSURE_ID));
baro_temperature.setPortId(paramsGetIntegerValue(BAROMETER_TEMPERATURE_ID));
magnetometer.setPortId(paramsGetIntegerValue(PARAM_MAGNETOMETER_ID));
Expand Down
8 changes: 0 additions & 8 deletions src/autopilot_interface/cyphal_hitl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,10 +45,6 @@ class CyphalHitlInterface {
esc_feedback_3(&cyphal, 0),
esc_feedback{{&esc_feedback_0, &esc_feedback_1, &esc_feedback_2, &esc_feedback_3}},
gps_gnss(&cyphal, 0),
gps_point(&cyphal, 0),
gps_sats(&cyphal, 0),
gps_status(&cyphal, 0),
gps_pdop(&cyphal, 0),
accel(&cyphal, 0),
gyro(&cyphal, 0),
imu(&cyphal, 0),
Expand Down Expand Up @@ -88,10 +84,6 @@ class CyphalHitlInterface {
std::array<cyphal::ZubaxCompactFeedbackPublisher*, 4> esc_feedback;

cyphal::Ds015GnssGnssPublisher gps_gnss;
cyphal::GpsPointPublisher gps_point;
cyphal::Int16Publisher gps_sats;
cyphal::Int16Publisher gps_status;
cyphal::Int16Publisher gps_pdop;

cyphal::BaroPressurePublisher baro_pressure;
cyphal::BaroTemperaturePublisher baro_temperature;
Expand Down
8 changes: 0 additions & 8 deletions src/autopilot_interface/params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,6 @@ IntegerDesc_t integer_desc_pool[] = {
{"uavcan.pub.baro.press.id", 1, 65535, 2404, MUTABLE, true},

{"uavcan.pub.ds015.gps.gnss.id", 1, 65535, 2005, MUTABLE, true},
{"uavcan.pub.gps.point.id", 1, 65535, 2406, MUTABLE, true},
{"uavcan.pub.gps.sats.id", 1, 65535, 2407, MUTABLE, true},
{"uavcan.pub.gps.status.id", 1, 65535, 2408, MUTABLE, true},
{"uavcan.pub.gps.pdop.id", 1, 65535, 2409, MUTABLE, true},

{"uavcan.pub.imu.accel.id", 1, 65535, 2400, MUTABLE, true},
{"uavcan.pub.imu.gyro.id", 1, 65535, 2401, MUTABLE, true},
Expand Down Expand Up @@ -56,10 +52,6 @@ StringDesc_t string_desc_pool[NUM_OF_STR_PARAMS] = {
{"uavcan.pub.baro.press.type", "uavcan.si.sample.pressure.Scalar", IMMUTABLE},

{"uavcan.pub.ds015.gps.gnss.type", "ds015.service.gnss.Gnss.0.1", IMMUTABLE},
{"uavcan.pub.gps.point.type", "reg.udral.physics.kinematics.geodetic.PointStateVarTs", IMMUTABLE},
{"uavcan.pub.gps.sats.type", "uavcan.primitive.scalar.Integer16", IMMUTABLE},
{"uavcan.pub.gps.status.type", "uavcan.primitive.scalar.Integer16", IMMUTABLE},
{"uavcan.pub.gps.pdop.type", "uavcan.primitive.scalar.Integer16", IMMUTABLE},

{"uavcan.pub.imu.accel.type", "uavcan.si.sample.acceleration.Vector3", IMMUTABLE},
{"uavcan.pub.imu.gyro.type", "uavcan.si.sample.angular_velocity.Vector3", IMMUTABLE},
Expand Down
6 changes: 1 addition & 5 deletions src/autopilot_interface/params.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,6 @@ enum IntParamsIndexes : ParamIndex_t {
BAROMETER_PRESSURE_ID,

PARAM_DS015_GPS_GNSS_ID,
PARAM_GPS_POINT_ID,
PARAM_GPS_SATS_ID,
PARAM_GPS_STATUS_ID,
PARAM_GPS_PDOP_ID,

IMU_ACCEL_ID,
IMU_GYRO_ID,
Expand All @@ -44,6 +40,6 @@ enum IntParamsIndexes : ParamIndex_t {
INTEGER_PARAMS_AMOUNT
};

#define NUM_OF_STR_PARAMS 25
#define NUM_OF_STR_PARAMS 21

#endif // PARAMS_HPP_

0 comments on commit c4e1f1e

Please sign in to comment.