Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions docs/en/camera/camera_architecture.md
Original file line number Diff line number Diff line change
Expand Up @@ -88,9 +88,9 @@ Commands supported in missions, including camera commands, are shown in these me
- Mission items are executed when set active.
- `issue_command(_mission_item)` is called at the end of this to send the current non-waypoint command
- [`MissionBlock::issue_command(const mission_item_s &item)`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/mission_block.cpp#L543-L562)
- Creates a vehicle command for the mission item then calls `publish_vehicle_cmd` to publish it (`_navigator->publish_vehicle_cmd(&vcmd);`)
- [`void Navigator::publish_vehicle_cmd(vehicle_command_s *vcmd)`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/navigator_main.cpp#L1358)
- For some camera commands it sets the component ID to the camera component id (`vcmd->target_component = 100; // MAV_COMP_ID_CAMERA`)
- Creates a vehicle command for the mission item then calls `publish_vehicle_command` to publish it (`_navigator->publish_vehicle_command(vehicle_command);`)
- [`void Navigator::publish_vehicle_command(vehicle_command_s &vehicle_command)`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/navigator_main.cpp#L1395)
- For some camera commands it sets the component ID to the camera component id (`vehicle_command.target_component = 100; // MAV_COMP_ID_CAMERA`)
- All others just get published to default component ID.
- The `VehicleCommand` UORB topic is published.

Expand Down
6 changes: 3 additions & 3 deletions docs/en/camera/mavlink_v2_camera.md
Original file line number Diff line number Diff line change
Expand Up @@ -83,11 +83,11 @@ void Mission::setActiveMissionItems() => https://github.com/PX4/PX4-Autopilot/bl
Issuing command:
MissionBlock::issue_command(const mission_item_s &item) => https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/mission_block.cpp#L543-L562
At end this publishes the current vehicle command
_navigator->publish_vehicle_cmd(&vcmd);
_navigator.publish_vehicle_command(vehicle_command);

Publishing command:
void Navigator::publish_vehicle_cmd(vehicle_command_s *vcmd) => https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/navigator_main.cpp#L1358
For camera commands set to vcmd->target_component = 100; // MAV_COMP_ID_CAMERA
void Navigator::publish_vehicle_command(vehicle_command_s &vehicle_command) => https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/navigator_main.cpp#L1395
For camera commands set to vehicle_command.target_component = 100; // MAV_COMP_ID_CAMERA
All others just get published as-is
-->

Expand Down
6 changes: 3 additions & 3 deletions docs/ko/camera/camera_architecture.md
Original file line number Diff line number Diff line change
Expand Up @@ -88,9 +88,9 @@ Commands supported in missions, including camera commands, are shown in these me
- Mission items are executed when set active.
- `issue_command(_mission_item)` is called at the end of this to send the current non-waypoint command
- [`MissionBlock::issue_command(const mission_item_s &item)`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/mission_block.cpp#L543-L562)
- Creates a vehicle command for the mission item then calls `publish_vehicle_cmd` to publish it (`_navigator->publish_vehicle_cmd(&vcmd);`)
- [`void Navigator::publish_vehicle_cmd(vehicle_command_s *vcmd)`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/navigator_main.cpp#L1358)
- For some camera commands it sets the component ID to the camera component id (`vcmd->target_component = 100; // MAV_COMP_ID_CAMERA`)
- Creates a vehicle command for the mission item then calls `publish_vehicle_command` to publish it (`_navigator->publish_vehicle_command(vehicle_command);`)
- [`void Navigator::publish_vehicle_command(vehicle_command_s &vehicle_command)`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/navigator_main.cpp#L1395)
- For some camera commands it sets the component ID to the camera component id (`vehicle_command.target_component = 100; // MAV_COMP_ID_CAMERA`)
- All others just get published to default component ID.
- The `VehicleCommand` UORB topic is published.

Expand Down
6 changes: 3 additions & 3 deletions docs/ko/camera/mavlink_v2_camera.md
Original file line number Diff line number Diff line change
Expand Up @@ -83,11 +83,11 @@ void Mission::setActiveMissionItems() => https://github.com/PX4/PX4-Autopilot/bl
Issuing command:
MissionBlock::issue_command(const mission_item_s &item) => https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/mission_block.cpp#L543-L562
At end this publishes the current vehicle command
_navigator->publish_vehicle_cmd(&vcmd);
_navigator->publish_vehicle_command(vehicle_command);

Publishing command:
void Navigator::publish_vehicle_cmd(vehicle_command_s *vcmd) => https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/navigator_main.cpp#L1358
For camera commands set to vcmd->target_component = 100; // MAV_COMP_ID_CAMERA
void Navigator::publish_vehicle_command(vehicle_command_s &vehicle_command) => https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/navigator_main.cpp#L1395
For camera commands set to vehicle_command.target_component = 100; // MAV_COMP_ID_CAMERA
All others just get published as-is
-->

Expand Down
6 changes: 3 additions & 3 deletions docs/uk/camera/camera_architecture.md
Original file line number Diff line number Diff line change
Expand Up @@ -88,9 +88,9 @@ PX4 повторно видає пункти камери, знайдені в
- Предмети місії виконуються, коли вони активовані.
- `issue_command(_mission_item)` викликається в кінці цього, щоб відправити поточну непунктову команду
- [`MissionBlock::видача_команди(const mission_item_s &item)`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/mission_block.cpp#L543-L562)
- Створює команду для місії транспортного засобу, а потім викликає `publish_vehicle_cmd` для публікації її (`_navigator->publish_vehicle_cmd(&vcmd);`)
- [`void Navigator::publish_vehicle_cmd(vehicle_command_s *vcmd)`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/navigator_main.cpp#L1358)
- Для деяких команд камери це встановлює ідентифікатор компонента на ідентифікатор компонента камери (`vcmd->target_component = 100; // MAV_COMP_ID_CAMERA`)
- Створює команду для місії транспортного засобу, а потім викликає `publish_vehicle_command` для публікації її (`_navigator->publish_vehicle_command(vehicle_command);`)
- [`void Navigator::publish_vehicle_command(vehicle_command_s &vehicle_command)`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/navigator_main.cpp#L1395)
- Для деяких команд камери це встановлює ідентифікатор компонента на ідентифікатор компонента камери (`vehicle_command.target_component = 100; // MAV_COMP_ID_CAMERA`)
- Усі інші просто публікуються під стандартний компонент ID.
- Тема UORB `VehicleCommand` публікується.

Expand Down
6 changes: 3 additions & 3 deletions docs/uk/camera/mavlink_v2_camera.md
Original file line number Diff line number Diff line change
Expand Up @@ -83,11 +83,11 @@ void Mission::setActiveMissionItems() => https://github.com/PX4/PX4-Autopilot/bl
Issuing command:
MissionBlock::issue_command(const mission_item_s &item) => https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/mission_block.cpp#L543-L562
At end this publishes the current vehicle command
_navigator->publish_vehicle_cmd(&vcmd);
_navigator->publish_vehicle_command(&vehicle_command);

Publishing command:
void Navigator::publish_vehicle_cmd(vehicle_command_s *vcmd) => https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/navigator_main.cpp#L1358
For camera commands set to vcmd->target_component = 100; // MAV_COMP_ID_CAMERA
void Navigator::publish_vehicle_command(vehicle_command_s &vehicle_command) => https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/navigator_main.cpp#L1395
For camera commands set to vehicle_command.target_component = 100; // MAV_COMP_ID_CAMERA
All others just get published as-is
-->

Expand Down
6 changes: 3 additions & 3 deletions docs/zh/camera/camera_architecture.md
Original file line number Diff line number Diff line change
Expand Up @@ -88,9 +88,9 @@ Commands supported in missions, including camera commands, are shown in these me
- Mission items are executed when set active.
- `issue_command(_mission_item)` is called at the end of this to send the current non-waypoint command
- [`MissionBlock::issue_command(const mission_item_s &item)`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/mission_block.cpp#L543-L562)
- Creates a vehicle command for the mission item then calls `publish_vehicle_cmd` to publish it (`_navigator->publish_vehicle_cmd(&vcmd);`)
- [`void Navigator::publish_vehicle_cmd(vehicle_command_s *vcmd)`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/navigator_main.cpp#L1358)
- For some camera commands it sets the component ID to the camera component id (`vcmd->target_component = 100; // MAV_COMP_ID_CAMERA`)
- Creates a vehicle command for the mission item then calls `publish_vehicle_command` to publish it (`_navigator->publish_vehicle_command(vehicle_command);`)
- [`void Navigator::publish_vehicle_command(vehicle_command_s &vehicle_command)`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/navigator_main.cpp#L1395)
- For some camera commands it sets the component ID to the camera component id (`vehicle_command.target_component = 100; // MAV_COMP_ID_CAMERA`)
- All others just get published to default component ID.
- The `VehicleCommand` UORB topic is published.

Expand Down
6 changes: 3 additions & 3 deletions docs/zh/camera/mavlink_v2_camera.md
Original file line number Diff line number Diff line change
Expand Up @@ -83,11 +83,11 @@ void Mission::setActiveMissionItems() => https://github.com/PX4/PX4-Autopilot/bl
Issuing command:
MissionBlock::issue_command(const mission_item_s &item) => https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/mission_block.cpp#L543-L562
At end this publishes the current vehicle command
_navigator->publish_vehicle_cmd(&vcmd);
_navigator->publish_vehicle_command(vehicle_command);

Publishing command:
void Navigator::publish_vehicle_cmd(vehicle_command_s *vcmd) => https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/navigator_main.cpp#L1358
For camera commands set to vcmd->target_component = 100; // MAV_COMP_ID_CAMERA
void Navigator::publish_vehicle_command(vehicle_command_s &vehicle_command) => https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/navigator/navigator_main.cpp#L1395
For camera commands set to vehicle_command.target_component = 100; // MAV_COMP_ID_CAMERA
All others just get published as-is
-->

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -235,7 +235,7 @@ void FlightTaskAuto::_prepareLandSetpoints()
bool range_dist_available = PX4_ISFINITE(_dist_to_bottom);

if (range_dist_available && _dist_to_bottom <= _param_mpc_land_alt3.get()) {
vertical_speed = _param_mpc_land_crawl_speed.get();
vertical_speed = _param_mpc_land_crwl.get();
}

if (_type_previous != WaypointType::land) {
Expand Down
14 changes: 5 additions & 9 deletions src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,20 +165,16 @@ class FlightTaskAuto : public FlightTask
(ParamFloat<px4::params::MPC_XY_TRAJ_P>) _param_mpc_xy_traj_p,
(ParamFloat<px4::params::MPC_XY_ERR_MAX>) _param_mpc_xy_err_max,
(ParamFloat<px4::params::MPC_LAND_SPEED>) _param_mpc_land_speed,
(ParamFloat<px4::params::MPC_LAND_CRWL>) _param_mpc_land_crawl_speed,
(ParamFloat<px4::params::MPC_LAND_CRWL>) _param_mpc_land_crwl,
(ParamInt<px4::params::MPC_LAND_RC_HELP>) _param_mpc_land_rc_help,
(ParamFloat<px4::params::MPC_LAND_RADIUS>) _param_mpc_land_radius,
(ParamFloat<px4::params::MPC_LAND_ALT1>)
_param_mpc_land_alt1, // altitude at which we start ramping down speed
(ParamFloat<px4::params::MPC_LAND_ALT2>)
_param_mpc_land_alt2, // altitude at which we descend at land speed
(ParamFloat<px4::params::MPC_LAND_ALT3>)
_param_mpc_land_alt3, // altitude where we switch to crawl speed, if LIDAR available
(ParamFloat<px4::params::MPC_LAND_ALT1>) _param_mpc_land_alt1,
(ParamFloat<px4::params::MPC_LAND_ALT2>) _param_mpc_land_alt2,
(ParamFloat<px4::params::MPC_LAND_ALT3>) _param_mpc_land_alt3,
(ParamFloat<px4::params::MPC_Z_V_AUTO_UP>) _param_mpc_z_v_auto_up,
(ParamFloat<px4::params::MPC_Z_V_AUTO_DN>) _param_mpc_z_v_auto_dn,
(ParamFloat<px4::params::MPC_TKO_SPEED>) _param_mpc_tko_speed,
(ParamFloat<px4::params::MPC_TKO_RAMP_T>)
_param_mpc_tko_ramp_t // time constant for smooth takeoff ramp
(ParamFloat<px4::params::MPC_TKO_RAMP_T>) _param_mpc_tko_ramp_t
);

private:
Expand Down
5 changes: 2 additions & 3 deletions src/modules/mc_pos_control/multicopter_takeoff_land_params.c
Original file line number Diff line number Diff line change
Expand Up @@ -89,9 +89,8 @@ PARAM_DEFINE_FLOAT(MPC_LAND_ALT2, 5.f);
/**
* Altitude for 3. step of slow landing
*
* Below this altitude descending velocity gets
* limited to "MPC_LAND_CRWL", if LIDAR available.
* No effect if LIDAR not available
* If a valid distance sensor measurement to the ground is available,
* limit descending velocity to "MPC_LAND_CRWL" below this altitude.
*
* @unit m
* @min 0
Expand Down
17 changes: 8 additions & 9 deletions src/modules/navigator/land.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,17 +109,16 @@ Land::on_active()
if (_navigator->abort_landing()) {

// send reposition cmd to get out of land mode (will loiter at current position and altitude)
vehicle_command_s vcmd = {};

vcmd.command = vehicle_command_s::VEHICLE_CMD_DO_REPOSITION;
vcmd.param1 = -1;
vcmd.param2 = 1;
vcmd.param5 = _navigator->get_global_position()->lat;
vcmd.param6 = _navigator->get_global_position()->lon;
vehicle_command_s vehicle_command{};
vehicle_command.command = vehicle_command_s::VEHICLE_CMD_DO_REPOSITION;
vehicle_command.param1 = -1.f; // Default speed
vehicle_command.param2 = 1.f; // Modes should switch, not setting this is unsupported
vehicle_command.param5 = _navigator->get_global_position()->lat;
vehicle_command.param6 = _navigator->get_global_position()->lon;
// as we don't know the landing point altitude assume the worst case (abort at 0m above ground),
// and thus always climb MIS_LND_ABRT_ALT
vcmd.param7 = _navigator->get_global_position()->alt + _navigator->get_landing_abort_min_alt();
vehicle_command.param7 = _navigator->get_global_position()->alt + _navigator->get_landing_abort_min_alt();

_navigator->publish_vehicle_cmd(&vcmd);
_navigator->publish_vehicle_command(vehicle_command);
}
}
18 changes: 8 additions & 10 deletions src/modules/navigator/mission_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -915,16 +915,14 @@ MissionBase::do_abort_landing()
}

// send reposition cmd to get out of mission
vehicle_command_s vcmd = {};

vcmd.command = vehicle_command_s::VEHICLE_CMD_DO_REPOSITION;
vcmd.param1 = -1;
vcmd.param2 = 1;
vcmd.param5 = _mission_item.lat;
vcmd.param6 = _mission_item.lon;
vcmd.param7 = alt_sp;

_navigator->publish_vehicle_cmd(&vcmd);
vehicle_command_s vehicle_command{};
vehicle_command.command = vehicle_command_s::VEHICLE_CMD_DO_REPOSITION;
vehicle_command.param1 = -1.f; // Default speed
vehicle_command.param2 = 1.f; // Modes should switch, not setting this is unsupported
vehicle_command.param5 = _mission_item.lat;
vehicle_command.param6 = _mission_item.lon;
vehicle_command.param7 = alt_sp;
_navigator->publish_vehicle_command(vehicle_command);
}

void MissionBase::publish_navigator_mission_item()
Expand Down
36 changes: 18 additions & 18 deletions src/modules/navigator/mission_block.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -529,27 +529,27 @@ MissionBlock::issue_command(const mission_item_s &item)

// Mission item's NAV_CMD enums directly map to the according vehicle command
// So set the raw value directly (MAV_FRAME_MISSION mission item)
vehicle_command_s vcmd = {};
vcmd.command = item.nav_cmd;
vcmd.param1 = item.params[0];
vcmd.param2 = item.params[1];
vcmd.param3 = item.params[2];
vcmd.param4 = item.params[3];
vcmd.param5 = static_cast<double>(item.params[4]);
vcmd.param6 = static_cast<double>(item.params[5]);
vcmd.param7 = item.params[6];
vehicle_command_s vehicle_command{};
vehicle_command.command = item.nav_cmd;
vehicle_command.param1 = item.params[0];
vehicle_command.param2 = item.params[1];
vehicle_command.param3 = item.params[2];
vehicle_command.param4 = item.params[3];
vehicle_command.param5 = static_cast<double>(item.params[4]);
vehicle_command.param6 = static_cast<double>(item.params[5]);
vehicle_command.param7 = item.params[6];

if (item.nav_cmd == NAV_CMD_DO_SET_ROI_LOCATION) {
// We need to send out the ROI location that was parsed potentially with double precision to lat/lon because mission item parameters 5 and 6 only have float precision
vcmd.param5 = item.lat;
vcmd.param6 = item.lon;
vehicle_command.param5 = item.lat;
vehicle_command.param6 = item.lon;

if (item.altitude_is_relative) {
vcmd.param7 = item.altitude + _navigator->get_home_position()->alt;
vehicle_command.param7 = item.altitude + _navigator->get_home_position()->alt;
}
}

_navigator->publish_vehicle_cmd(&vcmd);
_navigator->publish_vehicle_command(vehicle_command);

if (item_has_timeout(item)) {
_timestamp_command_timeout = hrt_absolute_time();
Expand Down Expand Up @@ -781,11 +781,11 @@ MissionBlock::set_land_item(struct mission_item_s *item)
/* VTOL transition to RW before landing */
if (_navigator->force_vtol()) {

vehicle_command_s vcmd = {};
vcmd.command = NAV_CMD_DO_VTOL_TRANSITION;
vcmd.param1 = vtol_vehicle_status_s::VEHICLE_VTOL_STATE_MC;
vcmd.param2 = 0.0f;
_navigator->publish_vehicle_cmd(&vcmd);
vehicle_command_s vehicle_command{};
vehicle_command.command = NAV_CMD_DO_VTOL_TRANSITION;
vehicle_command.param1 = vtol_vehicle_status_s::VEHICLE_VTOL_STATE_MC;
vehicle_command.param2 = 0.f; // normal unforced transition
_navigator->publish_vehicle_command(vehicle_command);
}

/* set the land item */
Expand Down
8 changes: 4 additions & 4 deletions src/modules/navigator/navigator.h
Original file line number Diff line number Diff line change
Expand Up @@ -132,12 +132,12 @@ class Navigator : public ModuleBase<Navigator>, public ModuleParams
/**
* @brief Publish a given specified vehicle command
*
* Sets the target_component of the vehicle command accordingly depending on the
* vehicle command value (e.g. For Camera control, sets target system component id)
* Fill in timestamp, source and target IDs.
* target_component special handling (e.g. For Camera control, set camera ID)
*
* @param vcmd Vehicle command to execute
* @param vehicle_command Vehicle command to publish
*/
void publish_vehicle_cmd(vehicle_command_s *vcmd);
void publish_vehicle_command(vehicle_command_s &vehicle_command);

#if CONFIG_NAVIGATOR_ADSB
/**
Expand Down
Loading
Loading