Frame ID when using setpoint commands

Hi,

I am trying OFFBOARD control of a rover using pixhawk set up with PX4. The Pixhawk is connected to a Jetson TX2 onboard the rover. I use the the IMU data from the Pixhawk along with wheel encoder data to perform localization which is published as a transform from the map frame to a chassis frame.

My question is, when we use the setpoint commands for OFFBOARD control, what frame id has to be published in the message? Would a missing or incorrect frame id in the message cause it not to work?

I tried different setpoint commands (position, velocity, raw) but no luck getting the rover to move. I am able to perform mode switching and arming successfully but the published setpoint commands don’t seem to have an effect.

Any help would be appreciated.

Thank you

We did some offboard control in the avoidance repo: here a link to the line where the offboard position setpoint is sent, you could use that as an example: https://github.com/PX4/avoidance/blob/86de5bdda843f73593148dda05b6ff6d35fdc5b1/local_planner/src/nodes/local_planner_node.cpp#L403

So to your question: I assume every frame known to mavros should technically work (fcu, local_origin, maybe others). Of course the frame must be specified and correct. You need to send you message with a certain minimum frequency (if I remember correctly at least 2 Hz), otherwise PX4 will reject the setpoints and switch back to position control. Once your setpoint stream is sent, you should only have to switch to Offboard mode from your Groundstation and the vehicle should follow the setpoints.

Thank you for the quick reply.
I looked at the code you mentioned and saw that you are using the cmd_vel_unstamped topic. This is what I tried.

  1. roslaunch mavros px4.launch, with the timesync_rate disabled to avoid the WARN: RTT too high for timesync.
  2. The tf now looks like as attached.
  3. I then run a node to publish Twist message on mavros/setpoint_velocity/cmd_vel_unstamped at 10 Hz. I defined each of the linear and angular velcoities as ros paramters and initialized them to 0.
  4. Once I have the above node running, I switch the mode to OFFBOARD and then arm the vehicle. Both these happen successfully.
  5. Now I use the rosparam command to change the values of linear and angular velocity being published.

I do this and still get no response from the rover.
I don’t know where I am going wrong.

Any suggestions would be helpful.
Thank you.

These are my mavros params:
CLEAR PARAMETERS

  • /mavros/

PARAMETERS

  • /mavros/cmd/use_comp_id_system_control: False
  • /mavros/conn/heartbeat_rate: 1.0
  • /mavros/conn/system_time_rate: 1.0
  • /mavros/conn/timeout: 10.0
  • /mavros/conn/timesync_rate: 0.0
  • /mavros/distance_sensor/hrlv_ez4_pub/field_of_view: 0.0
  • /mavros/distance_sensor/hrlv_ez4_pub/frame_id: hrlv_ez4_sonar
  • /mavros/distance_sensor/hrlv_ez4_pub/id: 0
  • /mavros/distance_sensor/hrlv_ez4_pub/orientation: PITCH_270
  • /mavros/distance_sensor/hrlv_ez4_pub/send_tf: True
  • /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/x: 0.0
  • /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/y: 0.0
  • /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/z: -0.1
  • /mavros/distance_sensor/laser_1_sub/id: 3
  • /mavros/distance_sensor/laser_1_sub/orientation: PITCH_270
  • /mavros/distance_sensor/laser_1_sub/subscriber: True
  • /mavros/distance_sensor/lidarlite_pub/field_of_view: 0.0
  • /mavros/distance_sensor/lidarlite_pub/frame_id: lidarlite_laser
  • /mavros/distance_sensor/lidarlite_pub/id: 1
  • /mavros/distance_sensor/lidarlite_pub/orientation: PITCH_270
  • /mavros/distance_sensor/lidarlite_pub/send_tf: True
  • /mavros/distance_sensor/lidarlite_pub/sensor_position/x: 0.0
  • /mavros/distance_sensor/lidarlite_pub/sensor_position/y: 0.0
  • /mavros/distance_sensor/lidarlite_pub/sensor_position/z: -0.1
  • /mavros/distance_sensor/sonar_1_sub/id: 2
  • /mavros/distance_sensor/sonar_1_sub/orientation: PITCH_270
  • /mavros/distance_sensor/sonar_1_sub/subscriber: True
  • /mavros/fake_gps/eph: 2.0
  • /mavros/fake_gps/epv: 2.0
  • /mavros/fake_gps/fix_type: 3
  • /mavros/fake_gps/geo_origin/alt: 408.0
  • /mavros/fake_gps/geo_origin/lat: 47.3667
  • /mavros/fake_gps/geo_origin/lon: 8.55
  • /mavros/fake_gps/gps_rate: 5.0
  • /mavros/fake_gps/mocap_transform: True
  • /mavros/fake_gps/satellites_visible: 5
  • /mavros/fake_gps/tf/child_frame_id: fix
  • /mavros/fake_gps/tf/frame_id: map
  • /mavros/fake_gps/tf/listen: False
  • /mavros/fake_gps/tf/rate_limit: 10.0
  • /mavros/fake_gps/tf/send: False
  • /mavros/fake_gps/use_mocap: True
  • /mavros/fake_gps/use_vision: False
  • /mavros/fcu_protocol: v2.0
  • /mavros/fcu_url: /dev/ttyUSB0:57600
  • /mavros/gcs_url:
  • /mavros/global_position/child_frame_id: base_link
  • /mavros/global_position/frame_id: map
  • /mavros/global_position/gps_uere: 1.0
  • /mavros/global_position/rot_covariance: 99999.0
  • /mavros/global_position/tf/child_frame_id: base_link
  • /mavros/global_position/tf/frame_id: map
  • /mavros/global_position/tf/global_frame_id: earth
  • /mavros/global_position/tf/send: False
  • /mavros/global_position/use_relative_alt: True
  • /mavros/image/frame_id: px4flow
  • /mavros/imu/angular_velocity_stdev: 0.000349065850399
  • /mavros/imu/frame_id: base_link
  • /mavros/imu/linear_acceleration_stdev: 0.0003
  • /mavros/imu/magnetic_stdev: 0.0
  • /mavros/imu/orientation_stdev: 1.0
  • /mavros/local_position/frame_id: map
  • /mavros/local_position/tf/child_frame_id: base_link
  • /mavros/local_position/tf/frame_id: map
  • /mavros/local_position/tf/send: False
  • /mavros/local_position/tf/send_fcu: False
  • /mavros/mission/pull_after_gcs: True
  • /mavros/mocap/use_pose: True
  • /mavros/mocap/use_tf: False
  • /mavros/odometry/in/child_frame_id: base_link
  • /mavros/odometry/in/frame_id: odom
  • /mavros/odometry/in/frame_tf/body_frame_orientation: flu
  • /mavros/odometry/in/frame_tf/local_frame: local_origin_ned
  • /mavros/odometry/out/frame_tf/body_frame_orientation: frd
  • /mavros/odometry/out/frame_tf/local_frame: vision_ned
  • /mavros/plugin_blacklist: [‘safety_area’, '…
  • /mavros/plugin_whitelist: []
  • /mavros/px4flow/frame_id: px4flow
  • /mavros/px4flow/ranger_fov: 0.118682389136
  • /mavros/px4flow/ranger_max_range: 5.0
  • /mavros/px4flow/ranger_min_range: 0.3
  • /mavros/safety_area/p1/x: 1.0
  • /mavros/safety_area/p1/y: 1.0
  • /mavros/safety_area/p1/z: 1.0
  • /mavros/safety_area/p2/x: -1.0
  • /mavros/safety_area/p2/y: -1.0
  • /mavros/safety_area/p2/z: -1.0
  • /mavros/setpoint_accel/send_force: False
  • /mavros/setpoint_attitude/reverse_thrust: False
  • /mavros/setpoint_attitude/tf/child_frame_id: target_attitude
  • /mavros/setpoint_attitude/tf/frame_id: map
  • /mavros/setpoint_attitude/tf/listen: False
  • /mavros/setpoint_attitude/tf/rate_limit: 50.0
  • /mavros/setpoint_attitude/use_quaternion: False
  • /mavros/setpoint_position/mav_frame: LOCAL_NED
  • /mavros/setpoint_position/tf/child_frame_id: target_position
  • /mavros/setpoint_position/tf/frame_id: map
  • /mavros/setpoint_position/tf/listen: False
  • /mavros/setpoint_position/tf/rate_limit: 50.0
  • /mavros/setpoint_raw/thrust_scaling: 1.0
  • /mavros/setpoint_velocity/mav_frame: LOCAL_NED
  • /mavros/startup_px4_usb_quirk: True
  • /mavros/sys/disable_diag: False
  • /mavros/sys/min_voltage: 10.0
  • /mavros/target_component_id: 1
  • /mavros/target_system_id: 1
  • /mavros/tdr_radio/low_rssi: 40
  • /mavros/time/time_ref_source: fcu
  • /mavros/time/timesync_avg_alpha: 0.6
  • /mavros/time/timesync_mode: MAVLINK
  • /mavros/vibration/frame_id: base_link
  • /mavros/vision_pose/tf/child_frame_id: vision_estimate
  • /mavros/vision_pose/tf/frame_id: map
  • /mavros/vision_pose/tf/listen: False
  • /mavros/vision_pose/tf/rate_limit: 10.0
  • /mavros/vision_speed/listen_twist: True
  • /mavros/vision_speed/twist_cov: True
  • /mavros/wheel_odometry/child_frame_id: base_link
  • /mavros/wheel_odometry/count: 2
  • /mavros/wheel_odometry/frame_id: map
  • /mavros/wheel_odometry/send_raw: True
  • /mavros/wheel_odometry/send_twist: False
  • /mavros/wheel_odometry/tf/child_frame_id: base_link
  • /mavros/wheel_odometry/tf/frame_id: map
  • /mavros/wheel_odometry/tf/send: True
  • /mavros/wheel_odometry/use_rpm: False
  • /mavros/wheel_odometry/vel_error: 0.1
  • /mavros/wheel_odometry/wheel0/radius: 0.05
  • /mavros/wheel_odometry/wheel0/x: 0.0
  • /mavros/wheel_odometry/wheel0/y: -0.15
  • /mavros/wheel_odometry/wheel1/radius: 0.05
  • /mavros/wheel_odometry/wheel1/x: 0.0
  • /mavros/wheel_odometry/wheel1/y: 0.15
  • /rosdistro: kinetic
  • /rosversion: 1.12.14

NODES
/
mavros (mavros/mavros_node)

ROS_MASTER_URI=http://localhost:11311

process[mavros-1]: started with pid [20916]
[ INFO] [1558464788.290501886]: FCU URL: /dev/ttyUSB0:57600
[ INFO] [1558464788.295183023]: serial0: device: /dev/ttyUSB0 @ 57600 bps
[ INFO] [1558464788.296668052]: GCS bridge disabled
[ INFO] [1558464788.350821730]: Plugin 3dr_radio loaded
[ INFO] [1558464788.357885414]: Plugin 3dr_radio initialized
[ INFO] [1558464788.358143462]: Plugin actuator_control loaded
[ INFO] [1558464788.384334140]: Plugin actuator_control initialized
[ INFO] [1558464788.396739199]: Plugin adsb loaded
[ INFO] [1558464788.425823976]: Plugin adsb initialized
[ INFO] [1558464788.426536878]: Plugin altitude loaded
[ INFO] [1558464788.433618353]: Plugin altitude initialized
[ INFO] [1558464788.434105747]: Plugin cam_imu_sync loaded
[ INFO] [1558464788.438499145]: Plugin cam_imu_sync initialized
[ INFO] [1558464788.439022407]: Plugin command loaded
[ INFO] [1558464788.493087808]: Plugin command initialized
[ INFO] [1558464788.494082306]: Plugin companion_process_status loaded
[ INFO] [1558464788.526164785]: Plugin companion_process_status initialized
[ INFO] [1558464788.527494282]: Plugin debug_value loaded
[ INFO] [1558464788.578460266]: Plugin debug_value initialized
[ INFO] [1558464788.578667760]: Plugin distance_sensor blacklisted
[ INFO] [1558464788.579473706]: Plugin fake_gps loaded
[ INFO] [1558464788.732992796]: Plugin fake_gps initialized
[ INFO] [1558464788.734053718]: Plugin ftp loaded
[ INFO] [1558464788.790266688]: Plugin ftp initialized
[ INFO] [1558464788.791021665]: Plugin global_position loaded
[ INFO] [1558464788.939001902]: Plugin global_position initialized
[ INFO] [1558464788.939907356]: Plugin gps_rtk loaded
[ INFO] [1558464788.973748525]: Plugin gps_rtk initialized
[ INFO] [1558464788.974481104]: Plugin hil loaded
[ INFO] [1558464789.120889276]: Plugin hil initialized
[ INFO] [1558464789.122349060]: Plugin home_position loaded
[ INFO] [1558464789.168985200]: Plugin home_position initialized
[ INFO] [1558464789.170254896]: Plugin imu loaded
[ INFO] [1558464789.273023485]: Plugin imu initialized
[ INFO] [1558464789.273575799]: Plugin local_position loaded
[ INFO] [1558464789.355878038]: Plugin local_position initialized
[ INFO] [1558464789.356926482]: Plugin log_transfer loaded
[ INFO] [1558464789.386520641]: Plugin log_transfer initialized
[ INFO] [1558464789.387113462]: Plugin manual_control loaded
[ INFO] [1558464789.420090876]: Plugin manual_control initialized
[ INFO] [1558464789.420738858]: Plugin mocap_pose_estimate loaded
[ INFO] [1558464789.455150426]: Plugin mocap_pose_estimate initialized
[ INFO] [1558464789.455765581]: Plugin obstacle_distance loaded
[ INFO] [1558464789.483388117]: Plugin obstacle_distance initialized
[ INFO] [1558464789.484022693]: Plugin odom loaded
[ INFO] [1558464789.560436137]: Plugin odom initialized
[ INFO] [1558464789.561657744]: Plugin param loaded
[ INFO] [1558464789.599784684]: Plugin param initialized
[ INFO] [1558464789.600721942]: Plugin px4flow loaded
[ INFO] [1558464789.698656611]: Plugin px4flow initialized
[ INFO] [1558464789.698771701]: Plugin rangefinder blacklisted
[ INFO] [1558464789.699557841]: Plugin rc_io loaded
[ INFO] [1558464789.739481291]: Plugin rc_io initialized
[ INFO] [1558464789.739580159]: Plugin safety_area blacklisted
[ INFO] [1558464789.740149591]: Plugin setpoint_accel loaded
[ INFO] [1558464789.759514288]: Plugin setpoint_accel initialized
[ INFO] [1558464789.759822697]: Plugin setpoint_attitude loaded
[ INFO] [1558464789.809180862]: Plugin setpoint_attitude initialized
[ INFO] [1558464789.810062959]: Plugin setpoint_position loaded
[ INFO] [1558464789.898066335]: Plugin setpoint_position initialized
[ INFO] [1558464789.899032870]: Plugin setpoint_raw loaded
[ INFO] [1558464789.986934659]: Plugin setpoint_raw initialized
[ INFO] [1558464789.988301687]: Plugin setpoint_velocity loaded
[ INFO] [1558464790.038974189]: Plugin setpoint_velocity initialized
[ INFO] [1558464790.039788327]: Plugin sys_status loaded
[ INFO] [1558464790.137676302]: Plugin sys_status initialized
[ INFO] [1558464790.139195919]: Plugin sys_time loaded
[ INFO] [1558464790.193279452]: TM: Timesync mode: MAVLINK
[ INFO] [1558464790.203495895]: Plugin sys_time initialized
[ INFO] [1558464790.204172418]: Plugin trajectory loaded
[ INFO] [1558464790.262563953]: Plugin trajectory initialized
[ INFO] [1558464790.263851119]: Plugin vfr_hud loaded
[ INFO] [1558464790.270397176]: Plugin vfr_hud initialized
[ INFO] [1558464790.270586432]: Plugin vibration blacklisted
[ INFO] [1558464790.271138714]: Plugin vision_pose_estimate loaded
[ INFO] [1558464790.363144037]: Plugin vision_pose_estimate initialized
[ INFO] [1558464790.364172772]: Plugin vision_speed_estimate loaded
[ INFO] [1558464790.409601010]: Plugin vision_speed_estimate initialized
[ INFO] [1558464790.411010145]: Plugin waypoint loaded
[ INFO] [1558464790.460253103]: Plugin waypoint initialized
[ INFO] [1558464790.460520045]: Plugin wheel_odometry blacklisted
[ INFO] [1558464790.461924700]: Plugin wind_estimation loaded
[ INFO] [1558464790.468775007]: Plugin wind_estimation initialized
[ INFO] [1558464790.469057979]: Autostarting mavlink via USB on PX4
[ INFO] [1558464790.469322330]: Built-in SIMD instructions: ARM NEON
[ INFO] [1558464790.469609206]: Built-in MAVLink package version: 2019.2.2
[ INFO] [1558464790.469870709]: Known MAVLink dialects: common ardupilotmega ASLUAV autoquad icarous matrixpilot paparazzi slugs standard uAvionix ualberta
[ INFO] [1558464790.470158769]: MAVROS started. MY ID 1.240, TARGET ID 1.1
[ INFO] [1558464790.677648605]: RC_CHANNELS message detected!
[ INFO] [1558464791.182722040]: CON: Got HEARTBEAT, connected. FCU: PX4 Autopilot
[ INFO] [1558464791.267209127]: RC_CHANNELS message detected!
[ INFO] [1558464791.502010553]: IMU: High resolution IMU detected!
[ INFO] [1558464792.227014851]: VER: 1.1: Capabilities 0x00000000000024ef
[ INFO] [1558464792.227680560]: VER: 1.1: Flight software: 01060500 (3098c77c9168553c)
[ INFO] [1558464792.228063104]: VER: 1.1: Middleware software: 01060500 (3098c77c9168553c)
[ INFO] [1558464792.228373433]: VER: 1.1: OS software: 000000c0 (0000000000000000)
[ INFO] [1558464792.228663732]: VER: 1.1: Board hardware: 00000011
[ INFO] [1558464792.228959311]: VER: 1.1: VID/PID: 26ac:0011
[ INFO] [1558464792.229246955]: VER: 1.1: UID: 3236511737353639
frames.pdf (17.4 KB)

Have you checked whether if offboard mode is supported in Rover?

Hi,
I came across a conversation on some dev work which hinted at it being on PX4.
https://gitter.im/mavlink/mavros/archives/2015/02/27
And coupled with a lot of forum posts about people getting it to work with ArduPilot’s GUIDED mode for a rover.
This is the reason I assumed it was supported.
Where can I find a confirmation of whether OFFBOARD is supported for the Rover platform on PX4?

Thanks for the message. You may have saved me some considerable time.

The last I remember when I tried to use PX4 with a rover that it doesn’t support OFFBOARD mode and I had to passthrough PWM commands directly and build our own position controller.

1 Like

Thank you all.
I have come to the same conclusion that setpoint commands dont work on the rover frame right now. Will be using mavros/actuator_controls for OFFBOARD control