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

Changes some frames from world to body conversion for NED to ENU. #208

Merged
merged 1 commit into from
Jun 12, 2015
Merged
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
2 changes: 1 addition & 1 deletion mavros/src/plugins/local_position.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ class LocalPositionPlugin : public MavRosPlugin {
* orientation in ENU, body-fixed
*/
tf::Transform transform;
transform.setOrigin(tf::Vector3(pos_ned.y, pos_ned.x, -pos_ned.z));
transform.setOrigin(tf::Vector3(pos_ned.x, -pos_ned.y, -pos_ned.z));
transform.setRotation(uas->get_attitude_orientation());

auto pose = boost::make_shared<geometry_msgs::PoseStamped>();
Expand Down
2 changes: 1 addition & 1 deletion mavros/src/plugins/setpoint_accel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ class SetpointAccelerationPlugin : public MavRosPlugin,
ignore_all_except_a_xyz,
0.0, 0.0, 0.0,
0.0, 0.0, 0.0,
afy, afx, -afz,
afx, -afy, -afz,
0.0, 0.0);
}

Expand Down
2 changes: 1 addition & 1 deletion mavros/src/plugins/setpoint_position.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,7 @@ class SetpointPositionPlugin : public MavRosPlugin,
set_position_target_local_ned(stamp.toNSec() / 1000000,
MAV_FRAME_LOCAL_NED,
ignore_all_except_xyz_y,
origin.y(), origin.x(), -origin.z(),
origin.x(), -origin.y(), -origin.z(),
0.0, 0.0, 0.0,
0.0, 0.0, 0.0,
tf::getYaw(q), 0.0);
Expand Down
2 changes: 1 addition & 1 deletion mavros/src/plugins/setpoint_velocity.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ class SetpointVelocityPlugin : public MavRosPlugin,
MAV_FRAME_LOCAL_NED,
ignore_all_except_v_xyz_yr,
0.0, 0.0, 0.0,
vy, vx, -vz,
vx, -vy, -vz,
0.0, 0.0, 0.0,
0.0, yaw_rate);
}
Expand Down
4 changes: 2 additions & 2 deletions mavros_extras/src/plugins/vision_pose_estimate.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -123,8 +123,8 @@ class VisionPoseEstimatePlugin : public MavRosPlugin,

// TODO: check conversion. Issue #49.
vision_position_estimate(stamp.toNSec() / 1000,
position.y(), position.x(), -position.z(),
roll, -pitch, -yaw); // ??? please check!
position.x(), -position.y(), -position.z(),
roll, -pitch, -yaw); // ??? please check!
}

/* -*- callbacks -*- */
Expand Down
2 changes: 1 addition & 1 deletion mavros_extras/src/plugins/visualization.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ class VisualizationPlugin : public MavRosPlugin {
mavlink_msg_local_position_ned_decode(msg, &pos_ned);

tf::Transform transform;
transform.setOrigin(tf::Vector3(pos_ned.y, pos_ned.x, -pos_ned.z));
transform.setOrigin(tf::Vector3(pos_ned.x, -pos_ned.y, -pos_ned.z));
transform.setRotation(uas->get_attitude_orientation());

auto pose = boost::make_shared<geometry_msgs::PoseStamped>();
Expand Down