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

Adds yaw offset property #6

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 3 additions & 1 deletion odometry.orogen
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,9 @@ task_context 'Generic' do
property('start_pose', '/base/samples/RigidBodyState').
doc "starting position for odometry"

property('yaw_offset', 'double', 0.0).
doc "adds this yaw to the body_to_IMUWorld"

##########################
# i/o ports
##########################
Expand Down Expand Up @@ -168,4 +171,3 @@ task_context 'ContactPointTask' do

port_driven 'dynamic_transformations'
end

6 changes: 6 additions & 0 deletions tasks/Skid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,6 +97,12 @@ void Skid::actuator_samplesTransformerCallback(const base::Time &ts, const base:

// calculates the rotation from body to world base on the orientation measurment
Eigen::Quaterniond R_body2World(body2IMUWorld.rotation());
double yaw_offset = _yaw_offset.get();
if( yaw_offset != 0 )
{
Eigen::AngleAxisd yaw(yaw_offset, Eigen::Vector3d::UnitZ());
R_body2World = yaw * R_body2World;
}

if(!usePosition)
{
Expand Down