soccer_pycontrol.navigator.Navigator
- class soccer_pycontrol.navigator.Navigator(real_time=False, display=True, useCalibration=True)[source]
Bases:
object
The 2D Navigator class, has a running loop that reads commands by the user and outputs actions to the soccerbot class. Doesn’t require ROS and used for unit tests. All functions called here should be related to pybullet simulation
- __init__(real_time=False, display=True, useCalibration=True)[source]
Initialize the Navigator
- Parameters:
display – Whether or not to show the pybullet visualization, turned off for quick unit tests
useCalibration – Whether or not to use movement calibration files located in config/robot_model.yaml, which adjusts the calibration to the movement given
Methods
__init__
([real_time, display, useCalibration])Initialize the Navigator
close
()getPose
()Get the 3D pose of the robot
ready
()Puts the robot into a ready pose to begin walking
run
([single_trajectory])The main run loop for the navigator, executes goals given through setGoal and then stops
setGoal
(goal)Set the goal of the robot, will create the path to the goal that will be executed in the run() loop
setPose
(pose)Relocate the robot at the certain pose
wait
(steps)Make the robot wait for a few steps
Attributes
PYBULLET_STEP
- run(single_trajectory=False) → bool[source]
The main run loop for the navigator, executes goals given through setGoal and then stops
- Parameters:
single_trajectory – If set to true, then the software will exit after a single trajectory is completed
- Returns:
True if the robot succeeds navigating to the goal, False if it doesn’t reach the goal and falls
- setGoal(goal: Transformation) → None[source]
Set the goal of the robot, will create the path to the goal that will be executed in the run() loop
- Parameters:
goal – The 3D location goal for the robot
- setPose(pose: Transformation) → None[source]
Relocate the robot at the certain pose
- Parameters:
pose – 3D pose of the robot