Skip to content
This repository was archived by the owner on Jul 10, 2025. It is now read-only.
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
1 change: 1 addition & 0 deletions gazebo_msgs/msg/LinkStates.msg
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
# broadcast all link states in world frame
Header header # stamp
string[] name # link names
geometry_msgs/Pose[] pose # desired pose in world frame
geometry_msgs/Twist[] twist # desired twist in world frame
1 change: 1 addition & 0 deletions gazebo_msgs/msg/ModelStates.msg
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
# broadcast all model states in world frame
Header header # stamp
string[] name # model names
geometry_msgs/Pose[] pose # desired pose in world frame
geometry_msgs/Twist[] twist # desired twist in world frame
5 changes: 5 additions & 0 deletions gazebo_ros/src/gazebo_ros_api_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2191,6 +2191,8 @@ void GazeboRosApiPlugin::publishSimTime()
void GazeboRosApiPlugin::publishLinkStates()
{
gazebo_msgs::LinkStates link_states;
link_states.header.stamp = ros::Time::now();
link_states.header.frame_id = "map";

// fill link_states
#if GAZEBO_MAJOR_VERSION >= 8
Expand Down Expand Up @@ -2248,6 +2250,9 @@ void GazeboRosApiPlugin::publishLinkStates()
void GazeboRosApiPlugin::publishModelStates()
{
gazebo_msgs::ModelStates model_states;
model_states.header.stamp = ros::Time::now();
model_states.header.frame_id = "map";


// fill model_states
#if GAZEBO_MAJOR_VERSION >= 8
Expand Down