Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Cannot set sensor orientation to YAW_45 #1688

Closed
MatCapLynx opened this issue Jan 6, 2022 · 7 comments
Closed

Cannot set sensor orientation to YAW_45 #1688

MatCapLynx opened this issue Jan 6, 2022 · 7 comments

Comments

@MatCapLynx
Copy link

Issue details

I'm trying to use a rangefinder (distance sensor) at a 45° angle in SITL with Gazebo. I've successfully set orientation to NONE, YAW_90, YAW_180, YAW_270.
For example for YAW_90, the sensor definition in my .sdf file is :

<!--right-facing lidar-->
    <include>
      <uri>model://lidar</uri>
      <pose>0 0 -0.1 0 0 -1.57079633</pose>
      <name>lidar1</name>
    </include>

Similarly for YAW_45, I used :

<!--45°-facing lidar-->
    <include>
      <uri>model://lidar</uri>
      <pose>0 0 -0.1 0 0 0.785398163</pose>
      <name>lidar4</name>
    </include>

But I get the following error : SENSOR: wrong orientation index: 100
From what I understood of https://github.com/mavlink/mavros/blob/master/mavros/src/lib/enum_sensor_orientation.cpp my orientation is considered as CUSTOM while it should be considered as YAW_45. Maybe this is a deg/rad conversion error or approximation. I've tried with several approximations of π/4.

MAVROS version and platform

Mavros: latest
ROS: Noetic
Ubuntu: 20.04

Autopilot type and version

[ ] ArduPilot
[ X ] PX4

Version: latest

Node logs

[ERROR] [1641489853.571286350, 184.549000000]: SENSOR: wrong orientation index: 100

Diagnostics

header: 
  seq: 15
  stamp: 
    secs: 193
    nsecs: 938000000
  frame_id: ''
status: 
  - 
    level: 0
    name: "mavros: FCU connection"
    message: "connected"
    hardware_id: "udp://:14540@localhost:14557"
    values: 
      - 
        key: "Received packets:"
        value: "3540"
      - 
        key: "Dropped packets:"
        value: "0"
      - 
        key: "Buffer overruns:"
        value: "0"
      - 
        key: "Parse errors:"
        value: "0"
      - 
        key: "Rx sequence number:"
        value: "230"
      - 
        key: "Tx sequence number:"
        value: "0"
      - 
        key: "Rx total bytes:"
        value: "206705"
      - 
        key: "Tx total bytes:"
        value: "5667"
      - 
        key: "Rx speed:"
        value: "27933.000000"
      - 
        key: "Tx speed:"
        value: "537.000000"
  - 
    level: 0
    name: "mavros: GPS"
    message: "3D fix"
    hardware_id: "udp://:14540@localhost:14557"
    values: 
      - 
        key: "Satellites visible"
        value: "10"
      - 
        key: "Fix type"
        value: "3"
      - 
        key: "EPH (m)"
        value: "0.00"
      - 
        key: "EPV (m)"
        value: "0.00"
  - 
    level: 1
    name: "mavros: Heartbeat"
    message: "Frequency too low."
    hardware_id: "udp://:14540@localhost:14557"
    values: 
      - 
        key: "Heartbeats since startup"
        value: "9"
      - 
        key: "Frequency (Hz)"
        value: "0.046407"
      - 
        key: "Vehicle type"
        value: "Quadrotor"
      - 
        key: "Autopilot type"
        value: "PX4 Autopilot"
      - 
        key: "Mode"
        value: "POSCTL"
      - 
        key: "System status"
        value: "Standby"
  - 
    level: 0
    name: "mavros: System"
    message: "Normal"
    hardware_id: "udp://:14540@localhost:14557"
    values: 
      - 
        key: "Sensor present"
        value: "0x3029002C"
      - 
        key: "Sensor enabled"
        value: "0x3021000C"
      - 
        key: "Sensor health"
        value: "0x302F002F"
      - 
        key: "3D magnetometer"
        value: "Ok"
      - 
        key: "absolute pressure"
        value: "Ok"
      - 
        key: "rc receiver"
        value: "Ok"
      - 
        key: "AHRS subsystem health"
        value: "Ok"
      - 
        key: "pre-arm check status. Always healthy when armed"
        value: "Ok"
      - 
        key: "Avoidance/collision prevention"
        value: "Ok"
      - 
        key: "CPU Load (%)"
        value: "28.0"
      - 
        key: "Drop rate (%)"
        value: "0.0"
      - 
        key: "Errors comm"
        value: "0"
      - 
        key: "Errors count #1"
        value: "0"
      - 
        key: "Errors count #2"
        value: "0"
      - 
        key: "Errors count #3"
        value: "0"
      - 
        key: "Errors count #4"
        value: "0"
  - 
    level: 0
    name: "mavros: Battery"
    message: "Normal"
    hardware_id: "udp://:14540@localhost:14557"
    values: 
      - 
        key: "Voltage"
        value: "16.20"
      - 
        key: "Current"
        value: "-1.0"
      - 
        key: "Remaining"
        value: "100.0"
  - 
    level: 0
    name: "mavros: Time Sync"
    message: "Normal"
    hardware_id: "udp://:14540@localhost:14557"
    values: 
      - 
        key: "Timesyncs since startup"
        value: "96"
      - 
        key: "Frequency (Hz)"
        value: "0.495004"
      - 
        key: "Last RTT (ms)"
        value: "1.000000"
      - 
        key: "Mean RTT (ms)"
        value: "0.229166"
      - 
        key: "Last remote time (s)"
        value: "9.764000000"
      - 
        key: "Estimated time offset (s)"
        value: "184.144288028"
---

Check ID

OK. I got messages from 1:1.

---
Received 7420 messages, from 2 addresses
sys:comp   list of messages
Exception in thread Thread-5:
Traceback (most recent call last):
  File "/usr/lib/python3.8/threading.py", line 932, in _bootstrap_inner
    self.run()
  File "/opt/ros/noetic/lib/python3/dist-packages/rospy/timer.py", line 237, in run
    self._callback(TimerEvent(last_expected, last_real, current_expected, current_real, last_duration))
  File "/home/mathieu/catkin_ws/src/mavros/mavros/scripts/checkid", line 82, in timer_cb
    for address, messages in self.message_sources.iteritems():
AttributeError: 'dict' object has no attribute 'iteritems'
@vooon
Copy link
Member

vooon commented Jan 8, 2022

What is your mavros configuraton? It doesn't read SDF, so somewhere must be set params section like that: https://github.com/mavlink/mavros/blob/ros2/mavros/launch/px4_config.yaml#L140

NOTE: it's possible to set custom rotation.

@MatCapLynx
Copy link
Author

MatCapLynx commented Jan 8, 2022

My config for this sensor is :

distance_sensor:
    rangefinder_pub4:
        id: 4
        frame_id: "lidar4"
        send_tf: true
        sensor_position: {x:  0.0, y:  0.0, z:  -0.1}
        field_of_view: 0.0

I've also tried with orientation :

rangefinder_pub4:
    id: 4
    orientation: YAW_45
    frame_id: "lidar4"
    send_tf: true
    sensor_position: {x:  0.0, y:  0.0, z:  -0.1}
    field_of_view: 0.0

but in this case I get another error :

[ERROR] [1641647988.732717328, 4.408000000]: SENSOR: wrong orientation index: 100
[ERROR] [1641647988.732796576, 4.408000000]: DS: rangefinder_pub4: received sensor data has different orientation (100) than in config (YAW_45)!

This is is what gave me the impression it read the SDF file.

@vooon vooon added the bug label Jan 9, 2022
@vooon
Copy link
Member

vooon commented Jan 9, 2022

I found bug in enum_sensor_orientation.cpp introduced by CUSTOM entry.

vooon added a commit that referenced this issue Jan 9, 2022
vooon added a commit that referenced this issue Jan 9, 2022
@vooon
Copy link
Member

vooon commented Jan 9, 2022

Could you please build master and test?

@MatCapLynx
Copy link
Author

I've built master and I don't get the SENSOR: wrong orientation index: 100 message anymore. My sensor orientation is now recognized as CUSTOM and it seems to be working.
But normally is should be recognized as YAW_45 and indeed I get the error message DS: rangefinder_pub4: received sensor data has different orientation (CUSTOM) than in config (YAW_45)!. Any clue to solve this ?

@vooon
Copy link
Member

vooon commented Jan 12, 2022

You have to modify simulator code to send different orientation because mavros plugin just checks if it matches config (like sanity check).
That's been essential before message been extended to have quaternion. Now it is likely that you can leave CUSTOM and just use tf frame which would have that rotation.

@MatCapLynx
Copy link
Author

Ok thanks !

chengguizi added a commit to chengguizi/mavros that referenced this issue Mar 26, 2022
* bugfix - add estimator type in odom message

Add missing estimator_type field in  Odometry message.
Issue mavlink#1524

* readme: add source install note for Noetic release

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* update changelog

* 1.5.2

* Fixed a bug in mavros_extras/src/plugins/odom.cpp by switching lines 175 and 180.

Rationale: The pose covariance matrix published to the /mavros/odometry/in topic is exclusively zeros. This is because the transformation matrix r_pose is initialised as zeros (line 140), then applied to the covariance matrix cov_pose (line 176) and then populated (line 180). Clearly the latter two steps should be the other way around, and the comments in the code appear to suggest that this was the intention, but that lines 175 and 180 were accidentally written the wrong way around. Having switched them, the pose covariance is now published to /mavros/odometry/in as expected.

JohnG897

* fix inconsistency in direction of yaw when using set_position in BODY frames and fix problems with yaw in setponit_raw

* update changelog

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* 1.6.0

* Fix mavlink#849

* README: Update PX4 Autopilot references

Much needed fixes to clarify the project is named correctly throughout the README
for the PX4 Autopilot, QGroundControl, and MAVLink

* MissionBase: breakout mission protocol from waypoint.cpp

* Waypoint: inherit MissionBase class for mission protocol

* Rallypoint: add rallypoint plugin

* Geofence: add geofence plugin

* add rallypoint and geofence plugins to CMakeList

* add rallypoint and geofence plugins to mavros plugins xml

* whitespace

* uncrustify

* MissionBase: add copyright from origional waypoint.cpp

* MissionBase: correction to file information

* plugins: mission: re-generate the code

* lib: re-generate the code

* msgs: re-generate the code

* update changelog

* 1.7.0

* re-generate all pymavlink enums

* update changelog

* 1.7.1

* convert whole expression to mm

* distance_sensor: Fill horizontal_fov, vertical_fov, quaternion

* distance_sensor: Add horizontal_fov_ratio, vertical_fov_ratio, sensor_orientation parameters

* px4_config: Add distance_sensor parameters

* extras: distance_sensor: rename param for custom orientation, apply uncrustify

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* lib: ftf: allow both Quaterniond and Quaternionf for quaternion_to_mavlink()

* extras: mavlink#1370: set obstacle aangle offset

* ci: install geographiclib datasets

* ci: github uses yaml parser which do not support anchors. surprise, surprise!

* Create codeql-analysis.yml

* Create semgrep-analysis.yml

* update changelog

* 1.8.0

* readme: update

* ci: remove travis

* ci: update industrial-ci usage

* Add compass calibration feedback status. Add service to call the 'Next' button in calibrations.

* Add message and service definition.

* Remove extra message from CMakeLists.

* Move Compass calibration report to extras. Rewrite code based on instructions.

* Set progress array to global to prevent erasing data.

* Apply uncrustify changes.

* Delete debug files.

* Exclude changes to launch files.

* Reset calibration flag when re-calibrating. Prevent wrong data output.

* Add Mount angles message for communications with ardupilotmega.

* added esc_telemetry plugin

* fixed some compile errors

* actually allocate memory for the telemetry information

* msgs: fix types for apm's esc telemetry

* extras: fix apm esc_telemetry

* extras: reformat plugins xml

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* plugins: reformat xml

* extras: uncrustify all plugins

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* extras: fix esc_telemetry centi-volt/amp conversion

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* extras: esc_telemetry: fix build

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* Remove Mount_Status plugin. Add Status data to Mount_Control plugin. Remove Mount_Status message.

* Add missing subscription.

* Publish quaternion information with Mount Status mavlink message.

* Convert status data from cdeg to rad.

* Update esc_status plugin with datatype change on MAVLink.

ESC_INFO MAVLink message was updated to have negative temperates and also at a different resolution. This commit updates those changes on this side.

Signed-off-by: Ricardo Marques <marques.ricardo17@gmail.com>

* Added GPS_INPUT plugin

* Added NAV_CONTROLLER_OUTPUT Plugin

* Mavlink v2.0 specs for RC_CHANNELS_OVERRIDE accepts upto 18 channels. The plugin publishes channels 9 to 18 if the FCU protocol version is 2.0

* publish BATTERY2 message as /mavros/battery2 topic

* This adds functionality to erase all logs on the SD card via mavlink

* Changed OverrideRCIn to 18 channels

* Spelling corrections

* update changelog

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* 1.9.0

* sys_time: publish /clock for simulation times

* sys_time.cpp: typo

* MountControl.msg: fix copy-paste

* mavros_msgs: Add Tunnel message

* mavros_extras: Create tunnel plugin

* Tunnel.msg: Generate enum with cog

* Tunnel: Check for invalid payload length

* Show ENOTCONN error instead of crash

When a client suddenly drops the connection,
socket.shutdown() will throw an exception:
boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::system::system_error> >
  what():  shutdown: Transport endpoint is not connected

Showing an error in this common case looks more reasonable than crashing.

* Catch std::length_error in send_message

Instead of crashing the process

* Remove reference

* msgs: update gpsraw to have yaw field

* prepare release

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* 1.10.0

* msgs: add yaw field to GPS_INPUT

* Add camera plugin for interfacing with mavlink camera protocol

Add camera image captured message for handling camera trigger information

* Address review comments

* distance_sensor: Initialize sensor orientation quaternion to zero

Without this, you'll get random garbage data for the quaternion field
of the DISTANCE_SENSOR MAVLink messages sent to the autopilot.

The quaternion field should be set to zero when unused, according to the
MAVLink message's field description.

* Use meters for relative altitude

* plugin: sys: Use wall timers for connection management

Fixes mavlink#1629

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* plugin: initialize quaternions with identity

Eigen::Quaternion[d|f] () does not initialize with zeroes or identity.
So we must initialize with identity vector objects that can be left
unassigned.

Related to mavlink#1652

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* plugin: sys: fix compillation error

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* msgs: try to hide 'unaligned pointer' warning

* plugin: setpoint_raw: fix misprint

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* msgs: fix convert const

* extras: landing_target: fix misprint

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* msgs: use pragmas to ignore unaligned pointer warnings

* lib: fix ftf warnings

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* update changelog

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* 1.11.0

* lib: fix build

* update changelog

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* 1.11.1

* extras: distance_sensor: revert back to zero quaternion

Fix mavlink#1653

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* lib: fix mission frame debug print

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* Fix multiple bugs

- fix bad_weak_ptr on connect and disconnect
- introduce new API to avoid thread race when assigning callbacks
- fix uninitialized variable in TCP client constructor which would
randomly block TCP server

This is an API breaking change: if client code creates connections using
make_shared<>() instead of open_url(), it is now necessary to call new
connect() method explicitly.

* update changelog

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* 1.12.0

* mavros: Fix some warnings

* mavros_extras: Fix some warnings

* mavconn: fix connection issue introduced by mavlink#1658

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* update changelog

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* 1.12.1

* extras: trajectory: backport mavlink#1667

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* plugin: setpoint_raw: move getParam to initializer

Repeatedly getting the thrust_scaling parameter in a callback that can
be invoked from a fast control loop may fail spuriously and trigger a
fatal error

* Set time/publish_sim_time to false by default

* update changelog

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* 1.12.2

* Add plugin for reporting terrain height estimate from FCU

* Fixed topic names to match more closely what other plugins use.  Fixed a typo.

* Add extra MAV_FRAMES to waypoint message as defined in https://mavlink.io/en/messages/common.html

* Fixed callback name to match `handle_{MESSAGE_NAME.lower()}` convention

* More explicitly state "TerrainReport" to allow for future extension of the plugin to support other terrain messages

* Removed CamelCase for class members.  Publish to "report"

* lib: Fix rotation search for CUSTOM

Fix mavlink#1688.

* test: add checks for ROTATION_CUSTOM

* re-generate all coglets

* py-lib: fix compatibility with py3 for Noetic

* update changelog

Signed-off-by: Vladimir Ermakov <vooon341@gmail.com>

* 1.13.0

Co-authored-by: Ashwin Varghese Kuruttukulam <35679537+ashwinvk94@users.noreply.github.com>
Co-authored-by: Vladimir Ermakov <vooon341@gmail.com>
Co-authored-by: John Gifford <john.gifford@leonardo-itg.com>
Co-authored-by: zhouzhiwen2000 <zhouzhiwen2000@gmail.com>
Co-authored-by: Tobias Fischer <info@tobiasfischer.info>
Co-authored-by: Ramon Roche <mrpollo@gmail.com>
Co-authored-by: Charlie-Burge <charlie.burge@manna.aero>
Co-authored-by: Thomas <thomas@rigi.tech>
Co-authored-by: Alexey Rogachevskiy <sfalexrog@gmail.com>
Co-authored-by: André Filipe <andre.ferreira@beyond-vision.pt>
Co-authored-by: BV-OpenSource <opensource@beyond-vision.pt>
Co-authored-by: Russell <russell@rizse.io>
Co-authored-by: Abhijith Thottumadayil Jagadeesh <abhijith@rizse.io>
Co-authored-by: Ricardo Marques <marques.ricardo17@gmail.com>
Co-authored-by: Dr.-Ing. Amilcar do Carmo Lucas <amilcar.lucas@iav.de>
Co-authored-by: Karthik Desai <karthik.desai@iav.de>
Co-authored-by: David Jablonski <dayjaby@gmail.com>
Co-authored-by: Morten Fyhn Amundsen <morten.fyhn.amundsen@gmail.com>
Co-authored-by: Val Doroshchuk <val@sevendof.com>
Co-authored-by: Marcelino Almeida <marcelino@pensasystems.com>
Co-authored-by: Jaeyoung-Lim <jalim@ethz.ch>
Co-authored-by: Alexander Sherikov <alexander@sevendof.com>
Co-authored-by: hs293go <hellston20a@gmail.com>
Co-authored-by: Oleg Kalachev <okalachev@gmail.com>
Co-authored-by: matt <anderson_rayner@hotmail.com>
Co-authored-by: Ubuntu <ubuntu@ubuntu1804.lxd>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

No branches or pull requests

2 participants