mavlink_receiver: refactor forgotten manual_control_setpoint naming

This commit is contained in:
Matthias Grob 2020-06-25 10:56:12 +02:00
parent f16286f3eb
commit 5579e319ff
3 changed files with 22 additions and 22 deletions

View File

@ -82,9 +82,9 @@ private:
void publishTorqueSetpoint(const hrt_abstime &timestamp_sample); void publishTorqueSetpoint(const hrt_abstime &timestamp_sample);
void publishThrustSetpoint(const hrt_abstime &timestamp_sample); void publishThrustSetpoint(const hrt_abstime &timestamp_sample);
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; /**< parameter updates subscription */ uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; /**< vehicle status subscription */ uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)};
uORB::Subscription _manual_control_sp_sub{ORB_ID(manual_control_setpoint)}; /**< manual control setpoint subscription */ uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)};
uORB::SubscriptionCallbackWorkItem _vehicle_angular_velocity_sub{this, ORB_ID(vehicle_angular_velocity)}; uORB::SubscriptionCallbackWorkItem _vehicle_angular_velocity_sub{this, ORB_ID(vehicle_angular_velocity)};
@ -92,10 +92,10 @@ private:
uORB::Publication<vehicle_thrust_setpoint_s> _vehicle_thrust_setpoint_pub{ORB_ID(vehicle_thrust_setpoint)}; uORB::Publication<vehicle_thrust_setpoint_s> _vehicle_thrust_setpoint_pub{ORB_ID(vehicle_thrust_setpoint)};
uORB::Publication<vehicle_torque_setpoint_s> _vehicle_torque_setpoint_pub{ORB_ID(vehicle_torque_setpoint)}; uORB::Publication<vehicle_torque_setpoint_s> _vehicle_torque_setpoint_pub{ORB_ID(vehicle_torque_setpoint)};
manual_control_setpoint_s _manual_control_sp {}; /**< manual control setpoint */ manual_control_setpoint_s _manual_control_setpoint{};
vehicle_status_s _vehicle_status {}; /**< vehicle status */ vehicle_status_s _vehicle_status{};
actuator_controls_s _actuator_controls {}; /**< actuator controls */ actuator_controls_s _actuator_controls{};
perf_counter_t _loop_perf; /**< loop performance counter */ perf_counter_t _loop_perf;
}; };

View File

@ -91,9 +91,9 @@ AirshipAttitudeControl::publish_actuator_controls()
} else { } else {
_actuator_controls.control[0] = 0.0f; _actuator_controls.control[0] = 0.0f;
_actuator_controls.control[1] = _manual_control_sp.x; _actuator_controls.control[1] = _manual_control_setpoint.x;
_actuator_controls.control[2] = _manual_control_sp.r; _actuator_controls.control[2] = _manual_control_setpoint.r;
_actuator_controls.control[3] = _manual_control_sp.z; _actuator_controls.control[3] = _manual_control_setpoint.z;
} }
// note: _actuator_controls.timestamp_sample is set in AirshipAttitudeControl::Run() // note: _actuator_controls.timestamp_sample is set in AirshipAttitudeControl::Run()
@ -150,7 +150,7 @@ AirshipAttitudeControl::Run()
publishThrustSetpoint(angular_velocity.timestamp_sample); publishThrustSetpoint(angular_velocity.timestamp_sample);
/* check for updates in manual control topic */ /* check for updates in manual control topic */
_manual_control_sp_sub.update(&_manual_control_sp); _manual_control_setpoint_sub.update(&_manual_control_setpoint);
/* check for updates in vehicle status topic */ /* check for updates in vehicle status topic */
_vehicle_status_sub.update(&_vehicle_status); _vehicle_status_sub.update(&_vehicle_status);

View File

@ -2129,22 +2129,22 @@ MavlinkReceiver::handle_message_rc_channels_override(mavlink_message_t *msg)
void void
MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg) MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg)
{ {
mavlink_manual_control_t man; mavlink_manual_control_t mavlink_manual_control;
mavlink_msg_manual_control_decode(msg, &man); mavlink_msg_manual_control_decode(msg, &mavlink_manual_control);
// Check target // Check target
if (man.target != 0 && man.target != _mavlink->get_system_id()) { if (mavlink_manual_control.target != 0 && mavlink_manual_control.target != _mavlink->get_system_id()) {
return; return;
} }
manual_control_setpoint_s manual{}; manual_control_setpoint_s manual_control_setpoint{};
manual.x = man.x / 1000.0f; manual_control_setpoint.x = mavlink_manual_control.x / 1000.0f;
manual.y = man.y / 1000.0f; manual_control_setpoint.y = mavlink_manual_control.y / 1000.0f;
manual.r = man.r / 1000.0f; manual_control_setpoint.r = mavlink_manual_control.r / 1000.0f;
manual.z = man.z / 1000.0f; manual_control_setpoint.z = mavlink_manual_control.z / 1000.0f;
manual.data_source = manual_control_setpoint_s::SOURCE_MAVLINK_0 + _mavlink->get_instance_id(); manual_control_setpoint.data_source = manual_control_setpoint_s::SOURCE_MAVLINK_0 + _mavlink->get_instance_id();
manual.timestamp = manual.timestamp_sample = hrt_absolute_time(); manual_control_setpoint.timestamp = manual_control_setpoint.timestamp_sample = hrt_absolute_time();
_manual_control_input_pub.publish(manual); _manual_control_input_pub.publish(manual_control_setpoint);
} }
void void