-
Notifications
You must be signed in to change notification settings - Fork 39
Lander Simulation
- Introduction
- Dynamics and Kinematic Modeling
- Robotic Arm
- Mast Pan/Tilt Head
- Power System
- Tables of Lander Activities
The OceanWATERS lander model features an antenna mast with a stereoscopic camera pair that can pivot up-down and left-right, a 6-degree-of-freedom (DOF) robotic arm that ends in a three-pronged end-effector selector, and a sample dock for collecting scooped material.
The simulated lander is modeled after the design developed by JPL for the
proposed Europa Lander Mission [SDT2016].
The lander model is simulated in Gazebo, with kinematic and dynamic properties
specified in Gazebo’s URDF (Unified Robotic Description Format) representation.
Lander URDF definition files are located in ow_lander/urdf
.
The underlying path-planning tool used in the simulator is MoveIt, a ROS package. MoveIt has several in-built motion planning algorithms. We have chosen the Rapidly-exploring Random Tree (RRT) algorithm for OceanWATERS. RRT particularly suits our specific application because the motion of the OceanWATERS lander arm is expected to be slow, and the expected component velocities are low. This means that dynamics effects would have a relatively low impact on the overall motion and forces. RRT*, a variant of RRT achieves asymptotic optimality, which means that an optimal solution will be found with a probability approaching one. RRT* is applicable to systems with simple dynamics, as it relies on the ability to connect any pair of states with an optimal trajectory. RRT* is more computationally intensive and, for this reason, it is used only for planning the sample delivery, and guarded move trajectories in order to have consistent solutions among different action calls. For all other motion planning activities, RRTConnect is used.
The arm and the mast pan-tilt unit are actuated by controllers using a kinematic
model. Arm joints are controlled by a proportional-derivative-integral (PID)
effort-based controller. For each arm activity, planning is performed using
MoveIt with targets given in joint space, Cartesian space or a combination
of both. The select MoveIt planner generates a list of waypoints representing
the trajectory that needs to be followed to get from the current state of the
arm to the desired state. Each waypoint has a list of positions, velocities and
accelerations for all joints involved in the current arm activity. The generated
trajectory is then sent to the effort_controller/JointTrajectoryController
for execution.
When planning an arm trajectory, MoveIt considers a simplified collision model to avoid interference with the lander body parts, as well as the masses and inertia of the rigid links. When executing a trajectory, Gazebo simulates both the kinematics and dynamics of the arm using Open Dynamics Engine (ODE).
The OceanWATERS lander arm is designed to acquire icy subsurface samples near the vicinity of the lander. The design of the lander arm consists of a 6-degree-of-freedom (DOF) manipulator with multiple end-effector tools for subsurface sample acquisition. Currently, a notional sample excavation tool and sample collection tool have been implemented. The trench excavation tool is modeled as a conventional grinder, which is capable of creating trenches in solid icy materials at depths greater than 10 cm. The sample collection tool, modeled after the Phoenix Mars Lander Robotic Arm (PML RA) scoop, is responsible for removing unwanted excavated trench material or loose surface material, collecting samples at a target depth, and transferring those samples to the Sample Transfer Dock (see Figure 1).
Figure 1 A: Shoulder link, B: Proximal link, C: Distal link, D: Wrist link, E: Hand link, F: Scoop link, G: Grinder link, a: Sample Transfer Dock
The lander arm is a 6 DOF arm with 7 links and 6 revolute joints. The 7 links are shoulder, proximal, distal, wrist, hand, scoop and grinder (A to G in Figure 1). The 6 joints are shoulder pitch, shoulder yaw, proximal pitch, distal pitch, hand yaw and scoop yaw. The grinder link is fixed to the hand in the simulation, although it could be considered to rotate about its longitudinal axis.
The arm can be programmed to move the end-effectors along particular directions and orientations to excavate and acquire samples. All arm activities are listed in Table of Arm Activities.
Arm activities are called via their ROS Actions interface. With ROS actions one can command the arm without blocking and receive real-time feedback about the end-effector's position. The autonomy package implements its PLEXIL commands using the very same ROS Action interface, and third-party autonomy modules may do the same.
ROS actions may be called from the command line using the action client scripts
provided in ow_lander/scripts
. The flags -h|--help
will reveal their
arguments and associated default values. For example:
./dig_circular_action_client.py --help
Arguments must be specified in the order they are listed in the help message. For all arguments not specified their default value will be used. The following ROS actions have been implemented in our simulation.
The lander starts in the default "Stowed" position. This is the configuration that consumes minimal power to maintain the arm in that position. To bring the arm to a stowed position from any other position use:
./stow_action_client.py
The Unstow command brings the arm to a safe configuration from which it is ready to perform any activity from any position. Typically use this command before using the arm for any other operation. Use the following command to use this feature.
./unstow_action_client.py`
Guarded move operation is used to detect the ground through arm motions. The arm is moved slowly near the ground and the the force torque sensor readings are used to detect the ground position. Ground detection at the default position can be used by the following command.
./guarded_move_action_client.py
The Guarded move command outputs the position of the ground. The Guarded move can be used at different location to generate a terrain profile. This can be used for grinding and digging activities.
A grinder is used as an excavation tool to trench hard materials before scoop can sample from the ground. The grinding start location and length of trench can be specified. The default grind operation can be run using:
./grind_action_client.py
After a grinding motion the scoop end effector can be used to dig out excavated or loose material. The scoop can perform circular motion at a particular position using the dig circular client.
./dig_circular_action_client.py
Dig out excavated or loose material with the scoop performing a linear trenching of the ground. This motion should also be performed after a Grind operation at the site. Default usage:
./dig_linear_action_client.py
After scoop has collected samples either through Dig Linear or Dig Circular operations, Deliver actions transfers the contents of the scoop to the Sample Transfer Dock. Use:
deliver_action_client.py
The purpose of this operation is to disregards tailings or unwanted samples. Discard action moves the contents of the scoop somewhere above the terrain. Use:
./discard_action_client.py
The ArmMoveJoint
action commands a specified arm joint. Its action
client script accepts three arguments: relative
, joint index
, and
joint angle
. relative
is a Boolean argument which when true moves
the joint relative to its the current position rather than an absolute
location. joint index
can take values from 0 to 5 which specify arm
joints as follows.
0:j_shou_yaw
1:j_shou_pitch
2:j_prox_pitch
3:j_dist_pitch
4:j_hand_yaw
5:j_scoop_yaw
joint angle
is the desired position of the joint given in radians.
Examples:
Move the shoulder yaw joint to 0.5 radians:
./arm_move_joint_client.py False 0 0.5
Move the shoulder pitch joint 0.5 radians from its current position:
./arm_move_joint_client.py True 1 0.5
The ArmMoveJoints
action commands all arm joints together. Its action
client script accepts two arguments: relative
and
joint angles
. relative
is a Boolean argument which when true moves
the joints relative to its the current positions rather than an absolute
location. joint angles
is the desired position of the joints given in radians
and the index corresponds to 1 to 5 in the following order.
0:j_shou_yaw
1:j_shou_pitch
2:j_prox_pitch
3:j_dist_pitch
4:j_hand_yaw
5:j_scoop_yaw
Example usage:
./arm_move_joints_client.py false 0.1 0.1 0.1 0.1 0.1 0.1
Important Note: Use of ArmMoveJoint/ArmMoveJoints can cause the arm to collide with the lander body and/or the terrain. Some, but not all, invalid motions will be denied by the motion planner (e.g. self-collision of the arm). Use this operation with extreme caution as it can break the simulation.
At any stage of arm movement or planning the arm motion can be stopped by the Stop client, Use:
./stop_action_client.py
Figure 2. The lander model with the distal pitch joint highlighted in red.
The arm has been equipped with an F/T sensor that measures forces and torques
that are applied on the distal pitch joint. The location of this joint can
be seen in Figure 2. The F/T sensor publishes its readings on the
/ft_sensor_dist_pitch
topic at a default rate of 200Hz. To view these readings
simply execute the following command:
rostopic echo /ft_sensor_dist_pitch
Each reading is represented as geometry_msgs/WrenchStamped message. All the values are expressed in reference to the child link of distal pitch joint which is l_wrist. The lander itself relies on readings of the F/T sensor when carrying some of its operations such as the guarded move activity.
Each reading is represented as geometry_msgs/WrenchStamped message. All the values are expressed in newton-metre with reference to the child link of distal pitch joint which is l_wrist. The lander itself relies on readings of the F/T sensor when carrying some of its operations such as the guarded move activity.
A high gain antenna is mounted on a pan/tilt head. The antenna is designed to cover the full sky. It is possible to point the antenna at a particular direction in the sky using the Antenna Pan & Tilt activity.
The lander has two spotlights on the top two corners of the antenna. The light
intensity can be individually adjusted for each spotlight using the ROS Service
/lander/light
. The name
argument accepts either "left"
or "right"
and
the intensity
argument must be in the inclusive range of 0.0 and 1.0.
The following would set both spotlights to 50% intensity.
rosservice call /lander/light right 0.5
rosservice call /lander/light left 0.5
For a better understanding of the illumination model used for both environment lights and lander lights, refer to the Illumination section.
The final step in the visual simulation pipeline is a camera simulation. Once images are rendered from the point of view of lander cameras, they are post-processed to simulate the characteristics of a digital camera. Specifically, the lander cameras are modeled after the Mars Science Laboratory (MSL) Mastcam-34 camera and have the following specifications:
-
34 mm focal length (21° x 15° FOV)
-
f/8 lens
-
ISO 1301
The camera simulation is implemented as a Gazebo plugin, which uses a GLSL
shader to generate the final rendered image. The plugin is used to simulate each
of the stereo cameras on the lander. Specifically, they are Gazebo Multicameras
and simulate two monocular cameras that can be simultaneously triggered by
either the left or right camera. The plugin is also utilized by the camera in
gzclient
, Gazebo’s GUI. Camera and image acquisition parameters are settable
via a number of ROS topics. Adjusting the settings on the gzclient
camera is
an easy way to preview what the lander will see if you make the same adjustments
to its cameras.
Figure 3. Camera image acquisition pipeline model.
The various steps involved in producing the final rendered camera image are illustrated in Figure 3. The circles between the rectangles represent the steps performed by our camera simulation.
The following ROS topics can be used to customize camera behavior. Camera
specific parameters (energy_conversion
, read_noise
, shot_noise
, and
adc_bits
) default to emulate MSL Mastcam-34 properties. The default exposure
is tuned to capture a properly exposed image in daylight on Europa. Sensor gain
and gamma default to having no effect.
ROS topic | Default Value | Units |
---|---|---|
/gazebo/plugins/camera_sim/exposure /gazebo/plugins/camera_sim/gui/exposure |
0.05 | seconds |
/gazebo/plugins/camera_sim/energy_conversion /gazebo/plugins/camera_sim/gui/energy_conversion |
0.005 | pixel value* per f-number lux second |
/gazebo/plugins/camera_sim/read_noise_std_dev /gazebo/plugins/camera_sim/gui/read_noise_std_dev |
0.8 | pixel value* |
/gazebo/plugins/camera_sim/shot_noise_coeff /gazebo/plugins/camera_sim/gui/shot_noise_coeff |
0.3 | n/a |
/gazebo/plugins/camera_sim/gain /gazebo/plugins/camera_sim/gui/gain |
1.0 | n/a |
/gazebo/plugins/camera_sim/gamma /gazebo/plugins/camera_sim/gui/gamma |
1.0 | n/a |
/gazebo/plugins/camera_sim/adc_bits /gazebo/plugins/camera_sim/gui/adc_bits |
12.0 | n/a |
* pixel values are integers in the interval [0, 2adc_bits - 1]
Converting light energy to sensor signal is a complex electronic process that
will be slightly different in each camera model. Since the details of the energy
conversion process may not be readily available for specific sensors or cameras,
we represent it with one settable value called energy_conversion
. A gamma
adjustment is not found in digital cameras, but we include it as a convenient
way to adjust what is seen in gzclient
. The bit-depth of analog-to-digital
converter sampling is called adc_bits
. Its effect will be invisible to the
human eye unless set very low (lower than 8), but it may have an effect on
computer image algorithms.
Any of these topics can be set while the simulation is running by issuing a command such as:
rostopic pub -1 /gazebo/plugins/camera_sim/exposure std_msgs/Float64 0.04
Remember to insert gui/ into the topic name if you want to affect the gzclient camera instead of the lander camera.
For additional usage details, see irg_open/irg_gazebo_plugins/src/IRGCameraSimPlugins/README.md
The lander is powered by a set of non-rechargeable lithium-ion battery packs to perform all its operations. Under the current operational requirements, the battery pack is discharged completely at the end of a mission. To support these requirements, it is crucial to understand the behavior of the battery pack system under different loading conditions and to capture its operation in the form of a developed first-principles model. The model can then be used to estimate the current health of the battery packs and predict end of discharge and remaining useful life (RUL), i.e. time to reach the lowest usable voltage based on future loading conditions. Note that the current integrated model simulates a single cell. A battery pack model comprising multiple cells is currently in development.
The modular Generic Software Architecture for Prognostics (GSAP) tool integrates a battery model and a prognostics algorithm. The prognostics algorithm employs a Monte Carlo framework to simulate the battery model open loop until a set lower threshold for state of charge is crossed. State of charge (SOC) is defined as the ratio of the available capacity Q(t) and the maximum possible charge that can be stored in a battery. The computationally efficient GSAP models capture electrochemical processes in the battery, estimate accurately its SOC, and predict battery voltage and temperature under different operating conditions of the lander. The prognostics algorithm output provides information to the autonomy module based on which the lander can be commanded to perform desired actions, based on the time of operation, SOC, RUL, the temperature of the battery pack, etc. Currently, there are limited reactionary measures taken by the autonomy node based on power system feedback.
The SOC, RUL, and temperature values are published on ROS topics each time a new average mechanical power output value is received from the lander. The average computing power and average power consumption from other lander functions such as cameras and thermal systems are currently not included in the power consumption estimates, so the power consumption parameter may need to be adjusted by the user for more specific cases. A mechanical to electrochemical power conversion model has been implemented to realistically represent the power requirements of the system.
Related faults may be injected to simulate power system failures or operations in battery-constrained situations. The types of faults and specific descriptions of the scenarios they simulate can be found in the Fault Injection and Modeling section of this user guide.
See Appendix A and [Daigle2013] for additional details.
Using the battery model described above, the ROS node implementing the power system takes into account the power used by joint actions, and it publishes three topics:
ROS topic | Description |
---|---|
/battery_state_of_charge |
Median estimation of the current battery voltage level. |
/battery_remaining_useful_life |
The current median prediction for time left until the end of discharge. |
/battery_temperature |
The current best estimate of battery temperature. |
The topics are published each time a new average mechanical power output value is received from the lander. The average computing power and average power consumption from other lander functions such as cameras and thermal systems are currently not included in the power consumption estimates, so the power consumption parameter may need to be adjusted by the user for more specific cases. A mechanical to electrochemical power conversion model has been implemented to realistically represent the power requirements of the system.
Faults may also be injected into the node described above to simulate power system failures or operations in battery- constrained situations. The types of faults and specific descriptions to the scenarios they simulate can be found in the Fault Injection and Modeling section of the user guide.
The different subsystems on-board the OceanWATERS lander can be commanded via ROS Actions. The activities and their associated action client scripts are summarized in the following tables.
Arm Activities | Description | ROS Action Client (in ow_lander/scripts ) |
---|---|---|
Stow | Bring the arm to a stowed configuration that consumes minimal power to maintain. | stow_action_client.py |
Unstow | Bring the arm to a safe configuration from which it is ready to perform any activity. | unstow_action_client.py |
Guarded Move | Poke the ground to determine surface positions. | guarded_move_action_client.py |
Grind | Use the excavation tool (grinder) to grind a trench out of hard material. | grind_action_client.py |
Dig Circular | Dig out excavated or loose material with the scoop performing a circular motion. | dig_circular_action_client.py |
Dig Linear | Dig out excavated or loose material with the scoop performing a linear motion. | dig_linear_action_client.py |
Deliver | Deliver contents of the scoop to the Sample Transfer Dock. | deliver_action_client.py |
Discard | Discard contents of the scoop somewhere above the terrain. | discard_action_client.py |
Move Joint | Move a single joint of the arm to a specified position or by a relative amount. | arm_move_joint_client.py |
Move Joints | Move all joints of the arm to specified positions or by relative amounts. | arm_move_joints_client.py |
Stop | Stop movement in the arm and terminate whatever activity it is executing. | stop_action_client.py |
Mast Activities | Description | ROS Action Client (in ow_lander/scripts ) |
---|---|---|
Antenna Pan & Tilt | Pan and/or tilt the antenna mast to specific positions. | antenna_pan_tilt_action_client.py |
Set Light Level | Change the intensity of each mast light individually. | Action not yet available, instead use rosservice call /lander/light "name: 'left' intensity: 0.0" where name is either "left" or "right" and intensity is a value between 0.0 and 1.0. |
Sample Dock Transfer Activities | Description | ROS Action Client (in ow_lander/scripts ) |
---|---|---|
Sample Ingest | Ingests sample contained inside the sample dock. | dock_ingest_sample_action_client.py |
[SDT2016] Europa Lander Science Definition Team Report
[Daigle2013] M. Daigle and C. Kulkarni, “Electrochemistry based Battery Modeling for Prognostics”, Annual Conference of the Prognostics and Health Management Society (PHM 2013), October 2013, New Orleans, LA.