Skip to content

Commit

Permalink
Fixed teleportation node
Browse files Browse the repository at this point in the history
  • Loading branch information
varundevsukhil committed Oct 22, 2019
1 parent 18e821f commit 4518818
Show file tree
Hide file tree
Showing 2 changed files with 29 additions and 13 deletions.
38 changes: 27 additions & 11 deletions src/set_racecar_state.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,27 +10,43 @@
if __name__ == '__main__':
try:
car_name = str(sys.argv[1])
pos_tuple = str(sys.argv[2])[1:-1].split(',')
vel_yuple = str(sys.argv[3])[1:-1].split(',')
x_pos = float(sys.argv[2])
y_pos = float(sys.argv[3])
z_pos = float(sys.argv[4])
x_vel = float(sys.argv[5])
y_vel = float(sys.argv[6])
z_vel = float(sys.argv[7])
frame_id = 'map'

rospy.init_node('teleport_node', anonymous = True)

teleport_pub = rospy.Publisher('/gazebo/set_model_state', ModelState, queue_size = 1)
teleport_info = ModelState()
pose = Pose()
twist = Twist()

teleport_info.pose.position.x = float(pos_tuple[0]) + 2.5
teleport_info.pose.position.y = float(pos_tuple[1]) - 7.5
teleport_info.pose.position.z = float(pos_tuple[2])
pose.position.x = x_pos
pose.position.y = y_pos
pose.position.z = z_pos

teleport_info.twist.linear.x = float(vel_tuple[0])
teleport_info.twist.linear.y = float(vel_tuple[1])
teleport_info.twist.linear.z = float(vel_tuple[2])
twist.linear.x = x_vel
twist.linear.y = y_vel
twist.linear.z = z_vel

teleport_info.model_name = car_name
teleport_info.model_name = car_name
teleport_info.pose = pose
teleport_info.twist = twist
teleport_info.reference_frame = frame_id

teleport_pub.publish(teleport_info)
rospy.Rate(1).sleep()
print('setting model state now')
print(teleport_pub)
print(teleport_info)

while not rospy.is_shutdown():
teleport_pub.publish(teleport_info)
rospy.Rate(0.2).sleep()

print('process completed')

except rospy.ROSInterruptException:
pass
4 changes: 2 additions & 2 deletions tutorials/expert_tutorials/expert_tutorials.md
Original file line number Diff line number Diff line change
Expand Up @@ -14,10 +14,10 @@ The node expects 2 additional arguments where each argument is a tuple. The firs
user@ros-computer: roslaunch f1tenth-sim simulator run_gazebo:=false
```

Observe the position of the racecar in the siulator GUI and launch a new terminal to enter the following command. The tuple contains 3 elements describing the information on each axis relative to the race track; for the first positional tuple, the structure is `(x_pos, y_pos, z_pos)` and for the second velocity tuple: `(x_vel, y_vel, z_vel)`. All data within the tuple must be a float for the node to work.
Observe the position of the racecar in the siulator GUI and launch a new terminal to enter the following command. The tuple contains 3 elements describing the information on each axis relative to the race track; for the first positional tuple, the structure is `x_pos y_pos z_pos` and for the second velocity tuple: `x_vel y_vel z_vel`. All data within the tuple must be a float for the node to work.

```console
user@ros-computer: rosrun f1tenth-sim set_racecar_state.py car_1 (0.0, 0.0, 5.0) (0.0, 0.0, 0.0)
user@ros-computer: rosrun f1tenth-sim set_racecar_state.py car_1 0.0 0.0 5.0 0.0 0.0 0.0
```

The first tuple commands the node to move the racecar to the origin of the race track and raise it to 5.0 meters above the surface of the race track. You can enter this command multiple times to get the same effect. If you wish to set the initial velocity of the racecar, modify the second tuple accordigly. It is important to note that the velocity tuple sets the velocity to the racecar as a physical object and no torque will be observeable on the wheels.
Expand Down

0 comments on commit 4518818

Please sign in to comment.