Using Collision Prevention

I want to test the PX4 Collision Prevention feature in a simulation environment. For this, I added a lidar to the drone and ensured a specific angle is covered. I populated the data into a variable I created from the px4_msgs::msg::ObstacleDistance message in ROS2 and publish it at certain intervals. However, the vehicle does not arm on the PX4 side. I am sharing the error I received and the parameters I changed via QGC in the images below. (The steps I followed are on this page).

PX4 Output

image

PX4 Parameter

Gz Sim Lidar Data:

code:

using obstacleDistanceMsg = px4_msgs::msg::ObstacleDistance;
obstacleDistanceMsg obs_distance;
obs_distance.frame = obs_distance.MAV_FRAME_BODY_FRD;
obs_distance.sensor_type = obs_distance.MAV_DISTANCE_SENSOR_LASER;
obs_distance.increment = 1;
obs_distance.min_distance = 8;
obs_distance.max_distance = 600;
obs_distance.angle_offset = -36;
void SensorListener::lidarCallabck(const laserScanMsg::SharedPtr msg)
{
    for(int i = 0; i < msg->ranges.size(); i++)
    {
        obs_distance.distances[i] = std::min(std::max(static_cast<int>(msg->ranges[i] * 1e2), static_cast<int>(obs_distance.min_distance)), static_cast<int>(obs_distance.max_distance));
    }
    obs_distance.timestamp =  px4_time;
    obstacle_distance->publish(obs_distance);
}
  • The right side is the system’s timestamp value, and the left side is the timestamp value I published.

@hamishwillee , have you done any work related to this?

@serkan I subedited / wrote some of the docs you point to working with the engineers who wrote this code. Unfortunately I’m an author - I haven’t actually tried this myself.

You’re not the only person to have had this problem [Bug] Avoidance system not ready · Issue #22994 · PX4/PX4-Autopilot · GitHub

It may be that there is some additional check for a companion computer. Have asked @Jaeyoung-Lim for advice on that issue - or a pointer to anyone who might know more.

Thank you for your response and guidance

if you just want e SITL envoirement for testing CP, download px4 Main, or a commit where this PR is present: [gz-sim] x500_lidar for testing CollisionPrevention by dakejahl · Pull Request #22418 · PX4/PX4-Autopilot · GitHub
with that you should be able to call make px4_sitl gz_x500_lidar
then you can enable CP in the Settings, but make sure to change MPC_POS_MODE to 0 or 3

I tried it, but it didn’t work very well. The drone is crashing into all the obstacles in front of it.

image

try with a higher cp_delay, as it scales the possible commanded velocities. and no delay is not realistic. and set mpc_jerk_max to the default value, if your halfing the jerk, your also increasing the delay related to velocity change, as your limiting the rate of change of acceleration.