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

35 sbg ros descriptions for the sbg devices #39

Open
wants to merge 2 commits into
base: devel
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
8 changes: 8 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -161,6 +161,14 @@ install(DIRECTORY config/
DESTINATION share/${PROJECT_NAME}/config
PATTERN ".git" EXCLUDE)

# Install URDF and meshes
install(DIRECTORY urdf/
DESTINATION share/${PROJECT_NAME}/urdf
)

install(DIRECTORY meshes/
DESTINATION share/${PROJECT_NAME}/meshes
)

###################################
## ament specific configuration ##
Expand Down
Binary file added meshes/ellipse.stl
Binary file not shown.
4 changes: 4 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,10 @@
<depend>tf2_geometry_msgs</depend>
<depend>nmea_msgs</depend>

<build_depend>urdf</build_depend>

<exec_depend>urdf</exec_depend>
<exec_depend>xacro</exec_depend>
<exec_depend>rosidl_default_runtime</exec_depend>

<member_of_group>rosidl_interface_packages</member_of_group>
Expand Down
4 changes: 2 additions & 2 deletions src/message_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1036,7 +1036,7 @@ const nav_msgs::msg::Odometry MessageWrapper::createRosOdoMessage(const sbg_driv
pose.position.y = first_valid_northing_;
pose.position.z = first_valid_altitude_;

fillTransform(odom_init_frame_id_, odom_frame_id_, pose, transform);
fillTransform(odom_init_frame_id_, odom_base_frame_id_, pose, transform);
tf_broadcaster_->sendTransform(transform);
static_tf_broadcaster_->sendTransform(transform);
}
Expand Down Expand Up @@ -1084,7 +1084,7 @@ const nav_msgs::msg::Odometry MessageWrapper::createRosOdoMessage(const sbg_driv
if (odom_publish_tf_)
{
// Publish odom transformation.
fillTransform(odo_ros_msg.header.frame_id, odom_base_frame_id_, odo_ros_msg.pose.pose, transform);
fillTransform(odom_base_frame_id_, odo_ros_msg.header.frame_id, odo_ros_msg.pose.pose, transform);
tf_broadcaster_->sendTransform(transform);
}

Expand Down
10 changes: 10 additions & 0 deletions urdf/ellipse.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
<robot name="ellipse">
<link name="odom">
<visual>
<origin xyz="0 0 0" rpy="1.5708 0 -1.5708"/> <!-- Add rotation to align the 3D model with odometry -->
<geometry>
<mesh filename="package://sbg_driver/meshes/ellipse.stl" scale="0.01 0.01 0.01"/>
</geometry>
</visual>
</link>
</robot>