I am using offboard mode with dronekit. But drone moves with very high jerk. I am sending position target as:
msg = self.vehicle.message_factory.set_position_target_global_int_encode(
0,
0, 0,
mavutil.mavlink.MAV_FRAME_GLOBAL,
0b101111111000,
x, y, z,
0, 0, 0,
0, 0, 0,
req_yaw_ang, 0)
self.vehicle.send_mavlink(msg)
self.vehicle.flush()
I got the same result with global or local frame.
PX4 Firmware v1.11.3 (Got the same result with v1.9.0)
SITL used with jmavsim ( Got the same result in real application)
I have tried to change MPC_JERK_MAX to minimum but no effect.
The purpose of offboard is to give you full control of the input to the position/velocity control loops.
So, if I’m not mistaken, when using offboard you need to take care about the full motion planning yourself.
If you want to benefit from the internal trajectory generator of PX4, then offboard might be the wrong solution for you. You might want to simply send desired waypoints through mavlink and start a mission like QGC does.
Oh so thats why auto parameters wont effects when using offboard. So how can I simply move 5 meters in x direction or north using mavlink? Can you point me to simple example?
You could try planning a mission with MAVSDK (we have an example here), or if you only want to move somewhere, you can use the goto example.
Otherwise we have a few offboard examples there, but as mentioned above, offboard is lower level, so you need to control the whole trajectory yourself.
Note that with a mission, you can set the “fly through” mode for waypoints (which should make it smoother), and soon you will be able to set the acceptance radius (see this PR).
Like @bresch said these parameters not used in offboard flight task. But it will be very nice to have an option to use the Velocity Smoothing utility when we are on offboard.
I have tried to implement a controller for speed but because of the jerk I couldn’t get smooth results.
@JonasVautherin goto can work for me. Wondering is there any way to drive with speed using Velocity Smoothing?
My goal is to follow an object which I detected with a companion computer. So smooth velocity setpoints would be great.
If you want to go down to setpoints, I think maybe you want offboard after all…
But MAVSDK has a “follow-me” plugin, where from MAVSDK you send the location and velocity of the object to follow, and PX4 does the following. Isn’t that what you want?
// Target location for the vehicle to follow
message TargetLocation {
double latitude_deg = 1 [(mavsdk.options.default_value)="NaN"]; // Target latitude in degrees
double longitude_deg = 2 [(mavsdk.options.default_value)="NaN"]; // Target longitude in degrees
float absolute_altitude_m = 3 [(mavsdk.options.default_value)="NaN"]; // Target altitude in meters above MSL
float velocity_x_m_s = 4 [(mavsdk.options.default_value)="NaN"]; // Target velocity in X axis, in meters per second
float velocity_y_m_s = 5 [(mavsdk.options.default_value)="NaN"]; // Target velocity in Y axis, in meters per second
float velocity_z_m_s = 6 [(mavsdk.options.default_value)="NaN"]; // Target velocity in Z axis, in meters per second
}