 behaviourcontrol | This namespace defines everything that is required for the Behaviour Control Framework |
  Behaviour | Implements a single behaviour |
  ActuatorManager | Implements a manager of a particular group of actuators |
  ActuatorBase | Implements a single actuator |
  Actuator | Implements a single actuator of a given data type |
  Sensor | Implements a single sensor of a given data type |
  BehaviourLayer | Implements a single behaviour layer |
   BBasePair | Data structure used to represent a basic inhibition pair, where behaviour A is taken to inhibit behaviour B |
  BehaviourManager | Implements a single behaviour manager |
  SensorManager | Implements a manager of a particular group of sensors |
  SensorBase | Implements a single sensor |
 cap_gait | This namespace defines everything that is required for the capture step gait |
  ComFilter | Filters a 2D CoM position, and calculates and smooths an estimate of the CoM velocity |
  CapGait | A capture step gait, implemented as a GaitEngine plugin for the Gait motion module |
  CapConfig | Configuration struct for the capture step gait |
 fall_protection | |
  FallProtection | Motion module that provides fall protection for the robot |
 field_model | |
  WorldObject | |
  FieldModel | Model of the soccer field |
 gait | Contains all classes necessary for the generic gait motion module |
  Gait | Generic gait motion module that can execute a given GaitEngine |
  GaitCommand | Gait command data structure |
  GaitEngine | Base implementation of a gait engine, made to work with the Gait motion module |
  GaitEngineInput | Data struct for passing gait engine input data from the generic gait motion module to the gait engine that it manages |
  GaitEngineOutput | Data struct for passing gait engine output data from the gait engine to the generic gait motion module that manages it |
  AbstractLegPose | Data struct that encompasses the abstract representation of a leg pose |
  AbstractArmPose | Data struct that encompasses the abstract representation of an arm pose |
  AbstractPose | Data struct that encompasses the abstract representation of a robot pose |
  CommonLegData | Data struct that contains the information pertaining to a leg pose that should be common amongst all pose representations |
  CommonArmData | Data struct that contains the information pertaining to an arm pose that should be common amongst all pose representations |
  InverseLegPose | Data struct that encompasses the inverse representation of a leg pose |
  InverseArmPose | Data struct that encompasses the inverse representation of an arm pose |
  InversePose | Data struct that encompasses the inverse representation of a robot pose |
  JointLegPose | Data struct that encompasses the joint representation of a leg pose |
  JointArmPose | Data struct that encompasses the joint representation of an arm pose |
  JointPose | Data struct that encompasses the joint representation of a robot pose |
 hash_lib | |
  CRC32 | Compute CRC32 hash, based on Intel's Slicing-by-8 algorithm |
  Keccak | Compute Keccak hash (designated SHA3) |
  MD5 | Compute MD5 hash |
  SHA1 | Compute SHA1 hash |
  SHA256 | Compute SHA256 hash |
  SHA3 | Compute SHA3 hash |
 margait_contrib | |
  RobotModelVis | Encapsulates a visualisation of the state of a RobotModel object |
 nimbro_op_interface | |
  RobotInterface | Real robot interface |
 nimbro_utils | This namespace defines a set of various utilities, both ROS dependent and ROS agnostic, that can be used for common fundamental tasks |
  RosTimeMarker | Class that facilitates the timing of durations using ROS-time |
  RosTimeTracker | Class that facilitates the timing of multiple durations using ROS-time |
  RosServiceCaller | Provides basic functionality for controlling calls to ROS services |
 statecontroller | This namespace defines everything that is required for the State Controller Library |
  GenState | Specialises the State class using templates to take care of the most common overloads |
  State | Implements a state that a state controller can be in |
  StateQueue | Implements a dynamic State queue |
  StateController | Base class for all state controllers |
 tf_tools | The namespace for all tf tools |
  FilteredListener | A class similar to tf::TransformListener , only with the ability to filter tf messages |
 walk_and_kick | This namespace defines everything that is required for the walk and kick behaviour node |
  BehDiveForBall | A walk and kick behaviour state that dives for the ball |
  BehDribbleBall | A walk and kick behaviour state that dribbles the ball towards a target |
  BehGoBehindBall | A walk and kick behaviour state that lines up the robot with the ball and a target |
  BehKickBall | A walk and kick behaviour state that kicks the ball towards a target |
  BehPanicAttack | A walk and kick behaviour state that induces a panic attack and stops the robot still |
  BehSearchForBall | A walk and kick behaviour state that searches for the ball |
  BehStopped | A walk and kick behaviour state that simply tells the robot to stop in place |
  BehUnknownState | A walk and kick behaviour state that stands in for an unknown state or ID |
  GazeBehLookAround | A walk and kick gaze behaviour state that looks around |
  GazeBehLookAtBall | A walk and kick gaze behaviour state that looks at the ball (and does not move the head from the last commanded pose if the ball is not seen) |
  GazeBehLookDown | A walk and kick gaze behaviour state that looks down |
  GazeBehLookForBall | A walk and kick gaze behaviour state that looks for the ball |
  GazeBehLookLeftRight | A walk and kick gaze behaviour state that looks left and right |
  WalkBehWalkToPose | A walk and kick walk behaviour state that makes the robot walk to a desired target pose on the field |
  GameDefaultBallHandling | A walk and kick game state that implements default ball handling for playing soccer |
  GameDefaultGoalie | A walk and kick game state that implements default goalie behaviours for playing soccer |
  GameGazeForBall | A walk and kick game state that makes the robot look for the ball by gaze only |
  GamePanicAttack | A walk and kick game state that induces a panic attack |
  GamePenaltyBallHandling | A walk and kick game state that implements ball handling for taking a penalty kick |
  GamePenaltyGoalie | A walk and kick game state that implements goalie behaviours for defending a penalty kick |
  GamePositioning | A walk and kick game state that forces the robot to the positioning behaviour state |
  GameStopped | A walk and kick game state that forces the robot to the stopped behaviour state |
  GameUnknownState | A walk and kick game state that stands in for an unknown state or ID |
  GameWaitForBallInPlay | A walk and kick game state that waits for the ball to be in play |
  ActuatorVars | An interface class for encapsulating all of the data that the walk and kick behaviour states should command |
  WAKBehManager | A class that manages and executes the walk and kick behaviour states |
  WAKBehShared | A class that shares the required walk and kick variables amongst the behaviour state classes |
  WAKBehState | The base class for all walk and kick behaviour states |
  WAKBehStateCombined | A walk and kick behaviour state that combines two others (which are assumed to operate independently) |
  WAKConfig | Configuration struct for the walk and kick node |
  WAKGameManager | A class that manages and executes the walk and kick game states |
  WAKGameShared | A class that shares the required walk and kick variables amongst the game state classes |
  DynamicTargetPose | Simple class that encapsulates the variables needed to easily dynamically calculate a target pose |
  WAKGameState | The base class for all walk and kick game states |
  GameVars | An interface class for encapsulating all of the data that the walk and kick game states should command |
  GCRosInterface | An interface class to the ROS world for getting game controller messages |
  GCVars | A class that encapsulates all of the game controller input data to the walk and kick node |
  WAKRosInterface | An interface class between the walk and kick and ROS worlds |
  SensorVars | An interface class for encapsulating all of the ROS input data to the walk and kick node |
  TCRosInterface | An interface class to the ROS world for team communications |
  TCRobotListener | A class that listens to the team communications data of one particular robot |
  TCVars | A class that encapsulates all of the team communication input data to the walk and kick node |
  TCRobotVars | A class that encapsulates all of the team communications data received from one particular robot |
  WAKUtils | A collection of independent helper functions that should be available to all |
  Counter | A simple counter class for counting events |
  TheWorm | A class that implements the worm, for making a live decision between two opposites |
  LiveTrapVelSpline | A wrapper class for the trapezoidal velocity spline class rc_utils::TrapVelSpline with a focus on smoothly supporting live updates of the spline |
  TrapVelSpline2D | A trapezoidal velocity spline that operates in 2D, based on the rc_utils::TrapVelSpline class |
  FieldDimensions | A simple class for abstracting away the source of the field dimensions |
  WAKMarkerMan | Visualisation marker manager for the walk and kick node |
  WAKBagMarkerMan | Visualisation marker manager for visualisations that are intended for when playing behaviour bags |
  WalkAndKick | The main walk and kick behaviour class |
 BallDetector | For detecting at least 50% white ball |
 ballParamC | Parameters container class for ball detection |
 BoundaryLineInterpolation | A class for interpolating between boundaries |
 calibC | Parameters container class for camera calibration |
 Camera | This class is responsible for image acquisition process
As an output this class provides the raw image in /vision/takenImg topic |
 cameraC | Parameters container class for camera |
 CameraCalibratorC | Parameters container class for camera calibration |
 CameraDummy | This class is responsible for imitating image acquisition process as a dummy replacement for Camera Class
As an input this class listen the raw image in /vision/takenImg topic |
 CameraProjections | For pixel projections |
 circleC | Parameters container class for circle detection |
 CircleDetector | For detecting center circle |
 ContourTester | A container class for testing countours |
 debugC | Parameters container class for debuging purposes |
 DistanceSizeS | A container class for distance-size calibration |
 DistortionModel | For undistortion |
 FieldDetector | For detecting field boundary |
 fieldParamC | Parameters container class for field detection |
 GoalDetector | For detecting potential goal posts |
 goalParamC | Parameters container class for goal detection |
 guiC | Parameters container class for gui |
 GuiManager | A container class for managing gui events |
 GuiRetS | A container class for gui rectangles |
 HillOptimizer | A class for hill climbing optimization |
 HSVPresenter | A class for showing HSV color range |
 hsvRangeC | HSV range class |
 igusParamC | Parameters container class for igus color |
 IPM | For Inverse Perspective Mapping |
 KalmanFilterC | A class for Kalman filter |
 LinearBoundaryChecker | A class for check if a point is between two given line segments |
 LinearInterpolator | A class for linearInterpolation |
 LineDetector | For detecting field lines |
 lineParamC | Parameters container class for line detection |
 LineSegment | A class representing line segments |
 LineSegmentTester | A class for visualize and test linesegments |
 Localization | For localization in the soccer field |
 localizationC | Parameters container class for localization |
 MatPublisher | A class for publish mat objects |
 ObstacleDetector | For detecting other robots with black feet |
 obstacleParamC | Parameters container class for obstacle detection |
 ParametersC | Parameters container class |
 SimplexOptimizer | Nelder–Mead optimization |
 sorter | For sorting operations on custom objects |
 tfC | Parameters container class for tf calibration |
 topViewC | Parameters container class for top view |
 Vision | This class is for managing all the required actions to find interesting objects in soccer field |
 VisionRate | For fixing the loop rate |
 VisionTimer | To set a timer and checked if the timeout exceeded |