fix spelling errors
This commit is contained in:
parent
23ee23fd65
commit
f4383f491b
|
@ -49,7 +49,7 @@ class xRockerBtn:
|
|||
|
||||
class PyGameJoyManager:
|
||||
def __init__(self, user_callback=None):
|
||||
self.dt = 0.01 # Sampling frequence of the joystick
|
||||
self.dt = 0.01 # Sampling frequency of the joystick
|
||||
self.running = False
|
||||
self.joy_thread_handle = threading.Thread(target=self.joy_thread)
|
||||
# an optional callback that can be used to send the reading values to a
|
||||
|
|
|
@ -82,7 +82,7 @@ class Go2Model:
|
|||
Calculates the inverse kinematics for the robot given a desired state.
|
||||
|
||||
Args:
|
||||
T (np.ndarray): The 4x4 homogenous transformation representing the pose of the base_link in the world frame
|
||||
T (np.ndarray): The 4x4 homogeneous transformation representing the pose of the base_link in the world frame
|
||||
x (np.ndarray): A numpy array of size 12 representing foot positions in world frame in FR, FL, RR, RL order.
|
||||
|
||||
Returns:
|
||||
|
|
|
@ -21,7 +21,7 @@ class Curriculum:
|
|||
self.grid <= high[:, None]
|
||||
).all(axis=0)
|
||||
|
||||
assert len(inds) != 0, "You are intializing your distribution with an empty domain!"
|
||||
assert len(inds) != 0, "You are initializing your distribution with an empty domain!"
|
||||
|
||||
self.weights[inds] = value
|
||||
|
||||
|
|
|
@ -20,7 +20,7 @@ class LeggedRobot(BaseTask):
|
|||
initial_dynamics_dict=None):
|
||||
""" Parses the provided config file,
|
||||
calls create_sim() (which creates, simulation, terrain and environments),
|
||||
initilizes pytorch buffers used during training
|
||||
initializes pytorch buffers used during training
|
||||
|
||||
Args:
|
||||
cfg (Dict): Environment config file
|
||||
|
@ -513,7 +513,7 @@ class LeggedRobot(BaseTask):
|
|||
self.privileged_obs_buf.shape[1]}), you will discard data from the student!"
|
||||
|
||||
def create_sim(self):
|
||||
""" Creates simulation, terrain and evironments
|
||||
""" Creates simulation, terrain and environments
|
||||
"""
|
||||
self.up_axis_idx = 2 # 2 for z, 1 for y -> adapt gravity accordingly
|
||||
self.sim = self.gym.create_sim(
|
||||
|
@ -1123,7 +1123,7 @@ class LeggedRobot(BaseTask):
|
|||
Velocities are set to zero.
|
||||
|
||||
Args:
|
||||
env_ids (List[int]): Environemnt ids
|
||||
env_ids (List[int]): Environment ids
|
||||
"""
|
||||
self.dof_pos[env_ids] = self.default_dof_pos * \
|
||||
torch_rand_float(0.5, 1.5, (len(env_ids), self.num_dof), device=self.device)
|
||||
|
@ -1142,7 +1142,7 @@ class LeggedRobot(BaseTask):
|
|||
Sets base position based on the curriculum
|
||||
Selects randomized base velocities within -0.5:0.5 [m/s, rad/s]
|
||||
Args:
|
||||
env_ids (List[int]): Environemnt ids
|
||||
env_ids (List[int]): Environment ids
|
||||
"""
|
||||
# base position
|
||||
if self.custom_origins:
|
||||
|
@ -1725,7 +1725,7 @@ class LeggedRobot(BaseTask):
|
|||
curriculum.set_to(low=low, high=high)
|
||||
|
||||
def _prepare_reward_function(self):
|
||||
""" Prepares a list of reward functions, whcih will be called to compute the total reward.
|
||||
""" Prepares a list of reward functions, which will be called to compute the total reward.
|
||||
Looks for self._reward_<REWARD_NAME>, where <REWARD_NAME> are names of all non zero reward scales in the cfg.
|
||||
"""
|
||||
# reward containers
|
||||
|
@ -2187,7 +2187,7 @@ class LeggedRobot(BaseTask):
|
|||
gymutil.draw_lines(sphere_geom, self.gym, self.viewer, self.envs[i], sphere_pose)
|
||||
|
||||
def _init_height_points(self, env_ids, cfg):
|
||||
""" Returns points at which the height measurments are sampled (in base frame)
|
||||
""" Returns points at which the height measurements are sampled (in base frame)
|
||||
|
||||
Returns:
|
||||
[torch.Tensor]: Tensor of shape (num_envs, self.num_height_points, 3)
|
||||
|
|
|
@ -9,7 +9,7 @@ class Cfg(PrefixProto, cli=False):
|
|||
num_observations = 235
|
||||
num_scalar_observations = 42
|
||||
# if not None a privilige_obs_buf will be returned by step() (critic obs
|
||||
# for assymetric training). None is returned otherwise
|
||||
# for asymmetric training). None is returned otherwise
|
||||
num_privileged_obs = 18
|
||||
privileged_future_horizon = 1
|
||||
num_actions = 12
|
||||
|
@ -228,7 +228,7 @@ class Cfg(PrefixProto, cli=False):
|
|||
# merge bodies connected by fixed joints. Specific fixed joints can be
|
||||
# kept by adding " <... dont_collapse="true">
|
||||
collapse_fixed_joints = True
|
||||
fix_base_link = False # fixe the base of the robot
|
||||
fix_base_link = False # fix the base of the robot
|
||||
# see GymDofDriveModeFlags (0 is none, 1 is pos tgt, 2 is vel tgt, 3 effort)
|
||||
default_dof_drive_mode = 3
|
||||
self_collisions = 0 # 1 to disable, 0 to enable...bitwise filter
|
||||
|
|
|
@ -57,7 +57,7 @@ Follow through the steps here to [setup](docs/setup.md) the robot and Go2Py.
|
|||
A set of examples and tutorials are provided to get you up and running quickly:
|
||||
|
||||
- [Communicating with the robot](examples/00-robot-interface.ipynb)
|
||||
- [Interracting with ROS2](examples/01-ros2-tools.ipynb)
|
||||
- [Interacting with ROS2](examples/01-ros2-tools.ipynb)
|
||||
- [Simulating with MuJoCo](examples/02-MuJoCo-sim.ipynb)
|
||||
- [Robot dynamics and kinematics](examples/03-robot-dynamic-model.ipynb)
|
||||
- [Finite state machine in low-level control](examples/04-FSM.ipynb)
|
||||
|
|
|
@ -111,7 +111,7 @@ ekf_filter_node:
|
|||
odom0_differential: false
|
||||
|
||||
# [ADVANCED] When the node starts, if this parameter is true, then the first measurement is treated as a "zero point"
|
||||
# for all future measurements. While you can achieve the same effect with the differential paremeter, the key
|
||||
# for all future measurements. While you can achieve the same effect with the differential parameter, the key
|
||||
# difference is that the relative parameter doesn't cause the measurement to be converted to a velocity before
|
||||
# integrating it. If you simply want your measurements to start at 0 for a given sensor, set this to true.
|
||||
odom0_relative: true
|
||||
|
|
|
@ -85,7 +85,7 @@ fi
|
|||
# Check if git-lfs is installed.
|
||||
git lfs &>/dev/null
|
||||
if [[ $? -ne 0 ]] ; then
|
||||
print_error "git-lfs is not insalled. Please make sure git-lfs is installed before you clone the repo."
|
||||
print_error "git-lfs is not installed. Please make sure git-lfs is installed before you clone the repo."
|
||||
exit 1
|
||||
fi
|
||||
|
||||
|
@ -115,7 +115,7 @@ if [ "$(docker ps -a --quiet --filter status=exited --filter name=$CONTAINER_NAM
|
|||
docker rm $CONTAINER_NAME > /dev/null
|
||||
fi
|
||||
|
||||
# Re-use existing container.
|
||||
# Reuse existing container.
|
||||
if [ "$(docker ps -a --quiet --filter status=running --filter name=$CONTAINER_NAME)" ]; then
|
||||
print_info "Attaching to running container: $CONTAINER_NAME"
|
||||
docker exec -i -t -u admin --workdir /workspaces/Go2Py $CONTAINER_NAME /bin/bash $@
|
||||
|
|
Loading…
Reference in New Issue