Base

class locobot.base.LoCoBotBase(configs, map_img_dir=None, base_controller='ilqr', base_planner=None, base=None)[source]

Bases: pyrobot.core.Base

This is a common base class for the locobot and locobot-lite base.

__init__(configs, map_img_dir=None, base_controller='ilqr', base_planner=None, base=None)[source]

The constructor for LoCoBotBase class.

Parameters:
  • configs (YACS CfgNode) – configurations read from config file
  • map_img_dir (string) – parent directory of the saved RGB images and depth images
get_state(state_type)[source]

Returns the requested base pose in the (x,y, yaw) format as computed either from Wheel encoder readings or Visual-SLAM

Parameters:state_type (string) – Requested state type. Ex: Odom, SLAM, etc
Returns:pose of the form [x, y, yaw]
Return type:list
go_to_absolute(xyt_position, use_map=False, close_loop=True, smooth=False)[source]

Moves the robot to the robot to given goal state in the world frame.

Parameters:
  • xyt_position (list or np.ndarray) – The goal state of the form (x,y,t) in the world (map) frame.
  • use_map (bool) – When set to “True”, ensures that controler is using only free space on the map to move the robot.
  • close_loop (bool) – When set to “True”, ensures that controler is operating in open loop by taking account of odometry.
  • smooth (bool) – When set to “True”, ensures that the motion leading to the goal is a smooth one.
go_to_relative(xyt_position, use_map=False, close_loop=True, smooth=False)[source]

Moves the robot to the robot to given goal state relative to its initial pose.

Parameters:
  • xyt_position (list or np.ndarray) – The relative goal state of the form (x,y,t)
  • use_map (bool) – When set to “True”, ensures that controler is using only free space on the map to move the robot.
  • close_loop (bool) – When set to “True”, ensures that controler is operating in open loop by taking account of odometry.
  • smooth (bool) – When set to “True”, ensures that the motion leading to the goal is a smooth one.
track_trajectory(states, controls=None, close_loop=True)[source]

State trajectory that the robot should track.

Parameters:
  • states (list) – sequence of (x,y,t) states that the robot should track.
  • controls (list) – optionally specify control sequence as well.
  • close_loop (bool) – whether to close loop on the computed control sequence or not.