in simulation_ws/src/robot_fleet/scripts/gazebo_model_mover.py [0:0]
def main(self):
rate = rospy.Rate(10.0)
while not rospy.is_shutdown():
all_active_data = {}
for name, data_w_timestamp in self.all_data.iteritems():
data = data_w_timestamp[0]
gazebo_pose = data['gazebo_pose']
robot_pose = Pose()
robot_pose.position.x = gazebo_pose['x']
robot_pose.position.y = gazebo_pose['y']
robot_pose.position.z = gazebo_pose['z']
robot_pose.orientation.x = gazebo_pose['qx']
robot_pose.orientation.y = gazebo_pose['qy']
robot_pose.orientation.z = gazebo_pose['qz']
robot_pose.orientation.w = gazebo_pose['qw']
if self.use_custom_move_plugin:
publisher = data_w_timestamp[2]
publisher.publish(robot_pose)
else:
model_state = ModelState()
model_state.model_name = name
model_state.pose = robot_pose
self.gazebo_set_state_pub.publish(model_state)
all_active_data[data['name']] = data
self.all_active_data_pub.publish(json.dumps(all_active_data))
rate.sleep()