osrf / drcsim

Repository for the DRC project.
16 stars 6 forks source link

continous joint is not limited to [ 0 : 2*pi ] #58

Closed osrf-migration closed 10 years ago

osrf-migration commented 11 years ago

Original report (archived issue) by Maurice Fallon (Bitbucket: mauricefallon).


I've added a continuously spinning joint with a laser - for the DRC robot's head to my own model:

#!c++

  <joint name="head_hokuyo_joint" type="continuous">
    <origin rpy="0 0 0" xyz="0 0 0"/>
    <axis xyz="1 0 0"/>
    <parent link="head"/>
    <child link="head_hokuyo"/>
    <limit effort="5" velocity="12"/>
    <safety_controller k_position="100.0" k_velocity="100.0" soft_lower_limit="-9.2146" soft_upper_limit="10.7854"/>
    <dynamics damping="0.1" friction="0"/>
  </joint>

However when i query the angle when spinning clockwise:

#!c++

double current_position = it->second->GetAngle(0).GetAsRadian();

... the angle is not limited to [ 0 : 2* pi]. And after some time is a value in the 100s. There seems to be no wrap around here.

This is probably a bug in gazebo itself.

osrf-migration commented 11 years ago

Original comment by Maurice Fallon (Bitbucket: mauricefallon).


osrf-migration commented 11 years ago

Original comment by Maurice Fallon (Bitbucket: mauricefallon).


osrf-migration commented 11 years ago

Original comment by John Hsu (Bitbucket: hsu, GitHub: hsu).


we've disabled joint wrapping in general for joints with limits, but you are right continuous joints should wrap, it's not immediately intuitive to me if it should wrap about (-pi, pi], or [0, 2*pi) or something else? configurable? If anyone has experience with wrapping of joint angles on different hardware platforms, I'd be interested to find out what they are. thanks.

osrf-migration commented 11 years ago

Original comment by Maurice Fallon (Bitbucket: mauricefallon).


Looking online I see more references to [0:2pi). We also have used that range for our velodyne driver.

I don't think it need be configurable - thats a pretty low level function

osrf-migration commented 11 years ago

Original comment by Steve Peters (Bitbucket: Steven Peters, GitHub: scpeters).


What about people who want to do wheel odometry with continuous joints? It seems like it would be convenient to have an unwrapped angle. Maybe we should just provide an accessor function that wraps?

osrf-migration commented 11 years ago

Original comment by Maurice Fallon (Bitbucket: mauricefallon).


For a real robot, you wouldnt do WO in that manner. You'd read differential readings and incorporate them into a DR filter with heading and covariance etc.

You wouldn't have access to the absolution number of rotations. For example in the real world you wouldn't turn on your real robot after 4 months and have knowledge of the number of rotations from 4 months previously.

osrf-migration commented 11 years ago

Original comment by John Hsu (Bitbucket: hsu, GitHub: hsu).


How about adding sdf for wrapping, e.g.:

<joint name="my_joint" type="revolute">
  <axis>
    <limit>
      <wrap>true</wrap>
      <wrap_max_angle>3.14</wrap_max_angle>
    </limit>
  </axis>
</joint>

Defaulting <wrap> to false, and default <wrap_max_angle> to 2*pi, and update Joint::GetAngle to respect the SDF specifications?

While internally, we expect physics engines to return unwrapped joint angles, but let Joint::Joint::GetAngle(...)` do the wrapping on the fly if requested by the user?

osrf-migration commented 11 years ago

Original comment by Maurice Fallon (Bitbucket: mauricefallon).


A real robot wouldn't be able give you this information, so I think the default should be true - so as to match a person's typical expections.

osrf-migration commented 11 years ago

Original comment by Steve Peters (Bitbucket: Steven Peters, GitHub: scpeters).


osrf-migration commented 11 years ago

Original comment by John Hsu (Bitbucket: hsu, GitHub: hsu).


osrf-migration commented 11 years ago

Original comment by John Hsu (Bitbucket: hsu, GitHub: hsu).


Please change title to something like: "add option to wrap simulation reported joint angles periodically between fixed values" and make this a feature request? Thanks.

osrf-migration commented 11 years ago

Original comment by Jesper Smith (Bitbucket: jespersmith).


On a real robot this would be depended on the sensor

a) differential, does not wrap, initializes to zero on bootup b) absolute one turn, wraps every turn c) absolute multiturn, wraps after multiple turns

osrf-migration commented 10 years ago

Original comment by John Hsu (Bitbucket: hsu, GitHub: hsu).


I think it's easier to go from untruncated angle to truncated angle, but much harder the other way around. So I am proposing to leave joint angles untruncated in simulation. It would be fairly easy to truncate angles in a controller plugin if needed. Thoughts?

osrf-migration commented 10 years ago

Original comment by John Hsu (Bitbucket: hsu, GitHub: hsu).


closed for now, please open issue in gazebo repo and sdformat repo if there's desire for wrapped joint angle as default. From simulation perspective, joint angle truncation is typically hardware induced, recommending a higher fidelity joint encoder sensor implementation, or wrapping the angle truncation code in the model plugin that exposes the hardware-like interfaces.