diff --git a/gazebo_msgs/msg/LinkStates.msg b/gazebo_msgs/msg/LinkStates.msg index 275dd1dd0..43c4fb905 100644 --- a/gazebo_msgs/msg/LinkStates.msg +++ b/gazebo_msgs/msg/LinkStates.msg @@ -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 diff --git a/gazebo_msgs/msg/ModelStates.msg b/gazebo_msgs/msg/ModelStates.msg index 1eac239a3..2f227a1fc 100644 --- a/gazebo_msgs/msg/ModelStates.msg +++ b/gazebo_msgs/msg/ModelStates.msg @@ -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 diff --git a/gazebo_ros/src/gazebo_ros_api_plugin.cpp b/gazebo_ros/src/gazebo_ros_api_plugin.cpp index 1eaa7bc0f..098bfc9b9 100644 --- a/gazebo_ros/src/gazebo_ros_api_plugin.cpp +++ b/gazebo_ros/src/gazebo_ros_api_plugin.cpp @@ -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 @@ -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