mirror of https://github.com/ArduPilot/ardupilot
AP_DDS: ensure zero rotation quaternions are normalised
- ROS expects quaternions to be normalised and the default message constructor does not enforce this. - Fix normalisation for pose stamped. Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com>
This commit is contained in:
parent
bd1a28c64c
commit
742db947cd
|
@ -232,6 +232,12 @@ void AP_DDS_Client::populate_static_transforms(tf2_msgs_msg_TFMessage& msg)
|
||||||
msg.transforms[i].transform.translation.y = -1 * offset[1];
|
msg.transforms[i].transform.translation.y = -1 * offset[1];
|
||||||
msg.transforms[i].transform.translation.z = -1 * offset[2];
|
msg.transforms[i].transform.translation.z = -1 * offset[2];
|
||||||
|
|
||||||
|
// Ensure rotation is normalised
|
||||||
|
msg.transforms[i].transform.rotation.x = 0.0;
|
||||||
|
msg.transforms[i].transform.rotation.y = 0.0;
|
||||||
|
msg.transforms[i].transform.rotation.z = 0.0;
|
||||||
|
msg.transforms[i].transform.rotation.w = 1.0;
|
||||||
|
|
||||||
msg.transforms_size++;
|
msg.transforms_size++;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -343,6 +349,11 @@ void AP_DDS_Client::update_topic(geometry_msgs_msg_PoseStamped& msg)
|
||||||
msg.pose.orientation.x = orientation[1];
|
msg.pose.orientation.x = orientation[1];
|
||||||
msg.pose.orientation.y = orientation[2];
|
msg.pose.orientation.y = orientation[2];
|
||||||
msg.pose.orientation.z = orientation[3];
|
msg.pose.orientation.z = orientation[3];
|
||||||
|
} else {
|
||||||
|
msg.pose.orientation.x = 0.0;
|
||||||
|
msg.pose.orientation.y = 0.0;
|
||||||
|
msg.pose.orientation.z = 0.0;
|
||||||
|
msg.pose.orientation.w = 1.0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -422,6 +433,11 @@ void AP_DDS_Client::update_topic(geographic_msgs_msg_GeoPoseStamped& msg)
|
||||||
msg.pose.orientation.x = orientation[1];
|
msg.pose.orientation.x = orientation[1];
|
||||||
msg.pose.orientation.y = orientation[2];
|
msg.pose.orientation.y = orientation[2];
|
||||||
msg.pose.orientation.z = orientation[3];
|
msg.pose.orientation.z = orientation[3];
|
||||||
|
} else {
|
||||||
|
msg.pose.orientation.x = 0.0;
|
||||||
|
msg.pose.orientation.y = 0.0;
|
||||||
|
msg.pose.orientation.z = 0.0;
|
||||||
|
msg.pose.orientation.w = 1.0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue