diff --git a/src/drivers/distance_sensor/tfmini_i2c/tfmini_i2c.cpp b/src/drivers/distance_sensor/tfmini_i2c/tfmini_i2c.cpp index bd0387237d..7cfb38fc87 100644 --- a/src/drivers/distance_sensor/tfmini_i2c/tfmini_i2c.cpp +++ b/src/drivers/distance_sensor/tfmini_i2c/tfmini_i2c.cpp @@ -280,6 +280,8 @@ TFMINI_I2C::collect() report.timestamp = hrt_absolute_time(); report.type = distance_sensor_s::MAV_DISTANCE_SENSOR_LASER; report.variance = 0.0f; + report.h_fov = math::radians(1.15f); + report.v_fov = math::radians(1.15f); int instance_id; orb_publish_auto(ORB_ID(distance_sensor), &_distance_sensor_topic, &report, &instance_id); diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 1cf60e82ba..6e38e2775b 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -737,6 +737,8 @@ Commander::handle_command(const vehicle_command_s &cmd) /* POSCTL */ reset_posvel_validity(); main_ret = main_state_transition(_status, commander_state_s::MAIN_STATE_POSCTL, _status_flags, _internal_state); + mavlink_log_info(&_mavlink_log_pub, "cmd mode:%d,ret:%d,lo:%d,go:%d\n",custom_main_mode,main_ret,_status_flags.condition_local_altitude_valid,_status_flags.condition_global_position_valid); + // main_ret = TRANSITION_CHANGED; } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) { /* AUTO */ diff --git a/src/modules/flight_mode_manager/tasks/ManualPosition/FlightTaskManualPosition.cpp b/src/modules/flight_mode_manager/tasks/ManualPosition/FlightTaskManualPosition.cpp index 5ef59be4bb..f30532b49f 100644 --- a/src/modules/flight_mode_manager/tasks/ManualPosition/FlightTaskManualPosition.cpp +++ b/src/modules/flight_mode_manager/tasks/ManualPosition/FlightTaskManualPosition.cpp @@ -114,6 +114,7 @@ void FlightTaskManualPosition::_scaleSticks() } _velocity_setpoint.xy() = vel_sp_xy; + } void FlightTaskManualPosition::_updateXYlock() diff --git a/src/modules/flight_mode_manager/tasks/ManualPosition/FlightTaskManualPosition.hpp b/src/modules/flight_mode_manager/tasks/ManualPosition/FlightTaskManualPosition.hpp index b0db7c3387..bcc906532b 100644 --- a/src/modules/flight_mode_manager/tasks/ManualPosition/FlightTaskManualPosition.hpp +++ b/src/modules/flight_mode_manager/tasks/ManualPosition/FlightTaskManualPosition.hpp @@ -76,4 +76,5 @@ private: nullptr; /**< external weathervane library, used to implement a yaw control law that turns the vehicle nose into the wind */ CollisionPrevention _collision_prevention; /**< collision avoidance setpoint amendment */ + orb_advert_t _mavlink_log_pub{nullptr}; ///< mavlink log pub };