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: |
|
---|
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: |
|
---|
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: |
|
---|
track_trajectory
(states, controls=None, close_loop=True)[source]¶State trajectory that the robot should track.
Parameters: |
|
---|