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

Distance sensor has a hardcoded "fcu" frame #835

Closed
AlexisTM opened this issue Oct 11, 2017 · 3 comments
Closed

Distance sensor has a hardcoded "fcu" frame #835

AlexisTM opened this issue Oct 11, 2017 · 3 comments

Comments

@AlexisTM
Copy link
Contributor

AlexisTM commented Oct 11, 2017

Problem:

The distance sensor frames are hardcoded. to fcu while we changed them all to base_link in PR #791

transform.header = m_uas->synchronized_header("fcu", dist_sen.time_boot_ms);
transform.child_frame_id = sensor->frame_id;

Solutions:

Adding a parameter fcu_frame_id to distance_sensor, yet, it interferes into the yaml parsing.

distance_sensor:
  fcu_frame_id: "base_link"
  hrlv_ez4_pub:
    id: 0
    frame_id: "hrlv_ez4_sonar"
    orientation: ROLL_180 # RPY:{180.0, 0.0, 0.0}
    field_of_view:  !degrees 3
    send_tf: true
    sensor_position: {x:  0.0, y:  0.0, z:  -0.1}

Or we can add a frame_id and child_frame_id parameters for every sensor. But it interferes with the current config of users if they just update to the new version.

distance_sensor:
  fcu_frame_id: "base_link"
  hrlv_ez4_pub:
    id: 0
    orientation: ROLL_180 # RPY:{180.0, 0.0, 0.0}
    field_of_view: !degrees 3
    send_tf: true
    sensor_position: {x:  0.0, y:  0.0, z:  -0.1}
    frame_id: "base_link"                            # UAV frame_id
    child_frame_id: "hrlv_ez4_sonar" # Distance sensor frame

Adding the hardcoded base_link is less versatile for custom setups.

@AlexisTM
Copy link
Contributor Author

A last solution can be to split parameters for TF:

distance_sensor:
  fcu_frame_id: "base_link"
  hrlv_ez4_pub:
    id: 0
    orientation: ROLL_180 # RPY:{180.0, 0.0, 0.0}
    field_of_view: !degrees 3
    sensor_position: {x:  0.0, y:  0.0, z:  -0.1}
    frame_id: "hrlv_ez4_sonar" # Distance sensor frame
    tf:
       send: true                  # send TF?
       frame_id: "base_link"  # fcu frame_id

@vooon vooon closed this as completed in 4b99177 Oct 11, 2017
@vooon
Copy link
Member

vooon commented Oct 11, 2017

I added base_frame_id as a base for all distance sensor parent frame_id.
But imho better do not use send_tf: preconfigure TF in URDF and set orientation (to check consistence between FCU and URDF).
That way you will use static tf, that save a lot of bandwidth.

@AlexisTM
Copy link
Contributor Author

It is indeed a better solution.

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