soccer_pycontrol.navigator_ros.NavigatorRos
- class soccer_pycontrol.navigator_ros.NavigatorRos(useCalibration=True)[source]
Bases:
Navigator
The Navigator class, receives commands from ROS and executes them in real life and in webots simulation. For functions common to both ROS and pybullet simulation, see
Navigator
- __init__(useCalibration=True)[source]
Initializes The NavigatorRos class
- Parameters:
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__
([useCalibration])Initializes The NavigatorRos class
close
()getPose
([footprint_name])Get the 3D pose of the robot
goal_callback
(pose)Callback function for when a new goal arrives.
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
update_robot_pose
([footprint_name])Function to update the location of the robot based on odometry.
wait
(steps)Make the robot wait for a few steps
Attributes
PYBULLET_STEP
- getPose(footprint_name='/base_footprint_gt')[source]
Get the 3D pose of the robot
- Returns:
The 3D pose of the robot
- goal_callback(pose: PoseStamped) → None[source]
Callback function for when a new goal arrives. It creates the path in the callback function and dynamically updates the current path if it exists (currently not working). Note the path computation occurs here instead of run because the computation will disturb the main thread. Main thread should still be running
- Parameters:
pose – The pose sent by the strategy for the robot to go to
- ready() → None
Puts the robot into a ready pose to begin walking
- run(single_trajectory=False)[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)[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)[source]
Relocate the robot at the certain pose
- Parameters:
pose – 3D pose of the robot