-
Notifications
You must be signed in to change notification settings - Fork 39
Lander Simulation
- Introduction
- Dynamics and Kinematic Modeling
- Robotic Arm
- Lander Antenna Mast
- Lander Tasks
- Power System
- Supplemental Activity Tables
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
.
When describing ROS Action Goal/Feedback/Result definitions the following shorthands are employed.
- Point refers to the geometry_msgs/Point message type
- Pose refers to the geometry_msgs/Pose message type
- Vector3 refers to the geometry_msgs/Vector3 message type
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 antenna 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.
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
/arm_end_effector_torque
topic at a default rate of 200Hz. To view these
readings simply execute the following command:
rostopic echo /arm_end_effector_torque
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 guarded arm movements and ArmFindSurface.
Joint states of the arm can be queried from the following topics. All message
definitions can be found in owl_msgs/msg
under the file with the same name as
the topic, but in CamelCase (e.g. the definition for the message broadcast on
/arm_joint_positions
is ArmJointPositions.msg
)
Topic | Units | Description |
---|---|---|
/arm_joint_positions |
rad | Absolute position of joint |
/arm_joint_velocties |
rad/s | Angular velocity of joint |
/arm_joint_accelerations |
rad/s^2 | Angular acceleration of joint |
/arm_joint_torques |
N·m | Torque or effort of joint |
Each joint telemetry topic consists of an float64 array of length 7. Each value in the array corresponds to a joint in the arm. The values are ordered alphabetically by the name of the joint they correspond to like in the following table. In the right column figures, the green arrow shows the axis of rotation of the joint.
Index | Joint Name | Joint Highlighted on Arm |
---|---|---|
0 | j_dist_pitch | |
1 | j_grinder | |
2 | j_hand_yaw | |
3 | j_prox_pitch | |
4 | j_scoop_yaw | |
5 | j_shou_pitch | |
6 | j_shou_yaw |
The pose of the scoop, specifically the l_scoop link, is constantly broadcast on
the /arm_pose
topic.
Arm activities are called via their ROS Actions interface. With ROS Actions one can command the arm without blocking. The autonomy package implements its PLEXIL commands using the ROS Action interface, and third-party autonomy module may do the same via the actionlib API.
ROS Actions may be called from the command line using the executable action
client scripts provided in ow_lander/scripts
. The flags -h|--help
will
reveal their arguments and associated default values. For example:
rosrun ow_lander arm_move_cartesian.py --help
The following ROS Actions have been implemented for control of the arm.
NOTE Sample handling actions, such as for digging a trench, can be found in the Lander Tasks section.
Moves end-effector to the commanded pose. If relative
is false, the value of
pose
will be interpreted as absolute in the selected frame. If relative
is
true, the value of pose
will be interpreted as relative to the current
end-effector pose in the selected frame.
ArmMoveCartesian | |
---|---|
Goal |
int32 frame bool relative Pose pose |
Feedback | Pose pose |
Result | Pose final_pose |
Client Script | arm_move_cartesian.py |
Moves end-effector to the commanded pose, but will stop if sufficient resistance
is encountered in the end-effector force/torque sensor. If relative
is false,
the value of pose
will be interpreted as absolute in the selected frame. If
relative
is true, the value of pose
will be interpreted as relative to the
current end-effector pose in the selected frame.
ArmMoveCartesianGuarded | |
---|---|
Goal |
int32 frame bool relative Pose pose float64 force_threshold float64 torque_threshold |
Feedback |
Pose pose float64 force float64 torque |
Result |
Pose final_pose float64 final_force float64 final_torque |
Client Script | arm_move_cartesian_guarded.py |
Moves the position of an arm joint. angle
is in radians. If relative
is
false, angle
is interpreted as an absolute joint position. If relative
is
true, angle
is interpreted as a position relative to its current position on
the joint's axis.
the joint will move to its current position plus the value of angle
.
ArmMoveJoint | |
---|---|
Goal |
bool relative int32 joint float64 angle |
Feedback | float64[7] angles |
Result | float64[7] final_angles |
Client Script | arm_move_joint.py |
WARNING Use of ArmMoveJoint 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.
The following table describes the possible values of joint
when using
ArmMoveJoint. It also explains the float64[7] array in the following
two actions, ArmMoveJoints and ArmMoveJointsGuarded. Note that the
7th index exists only to support OWLAT's 7 DoF arm and should be ignored
when using OceanWATERS, which has a 6 DoF arm. When constructing an array
of positions to be sent with ArmMoveJoints one can simply set the 7th
value to zero.
Index | Arm Joint |
---|---|
0 | shoulder yaw |
1 | shoulder pitch |
2 | proximal pitch |
3 | distal pitch |
4 | hand yaw |
5 | scoop yaw |
6 | ignored by OceanWATERS |
Moves the positions of all arm joints. Values of angles
are in radians. If
relative
is false, angles
values are interpreted as absolute joint
positions. If relative
is true, angles
values are interpreted as positions
relative to the corresponding joint's current position on its axis.
ArmMoveJoints | |
---|---|
Goal |
bool relative float64[7] angles |
Feedback | float64[7] angles |
Result | float64[7] final_angles |
Client Script | arm_move_joints.py |
Refer to the above table, Arm Joint Indices, for the semantics of the float64[7] arrays.
WARNING Use of 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.
Moves the positions of all arm joints, but will stop if sufficient resistance
is encountered in the end-effector force/torque sensor. Values of angles
are
in radians. If relative
is false, angles
values are interpreted as absolute
joint positions. If relative
is true, angles
values are interpreted as
positions relative to the corresponding joint's current position on its axis.
ArmMoveJointsGuarded | |
---|---|
Goal |
bool relative float64[7] angles float64 force_threshold float64 torque_threshold |
Feedback |
float64[7] angles float64 force float64 torque |
Result |
float64[7] final_angles float64 final_force float64 final_torque |
Client Script | arm_move_joints_guarded.py |
Refer to the above table, Arm Joint Indices, for the semantics of the float64[7] arrays.
Poke surface with the scoop end-effector. position
is the estimated surface
position that will be poked. If relative
is false, the value of position
will be interpreted as absolute in the selected frame. If relative
is true,
the value of position
will be interpreted as relative to the current
end-effector position in the selected frame. normal
is the estimated normal
of the surface, and will always be interpreted in the base_link
frame.
distance
is the distance along the normal
the poke trajectory will begin,
and overdrive
is the maximum distance the end-effector will drive past the
estimated surface position in the anti-normal direction.
ArmFindSurface | |
---|---|
Goal |
int32 frame bool relative Point position Vector3 normal float64 distance float64 overdrive float64 force_threshold float64 torque_threshold |
Feedback |
Pose pose float64 distance float64 force float64 torque |
Result |
Pose final_pose float64 final_distance float64 final_force float64 final_torque |
Client Script | arm_find_surface.py |
Immediately cease any arm movement or sample handling tasks and abort its corresponding ROS Action.
ArmStop | |
---|---|
Goal | none |
Feedback | none |
Result | none |
Client Script | arm_stop.py |
Move lander arm to stowed configuration. This is the same configuration that the arm starts the simulation in, and is the configuration that consumes the least amount of power to maintain.
ArmStow | |
---|---|
Goal | none |
Feedback | none |
Result | none |
Client Script | arm_stow.py |
Move lander arm to unstowed configuration. It is good practice to do this prior to most arm operations, so long as sample is not being held inside the scoop.
ArmUnstow | |
---|---|
Goal | none |
Feedback | none |
Result | none |
Client Script | arm_unstow.py |
Guarded move operation is used to detect the ground through arm motions. The arm is moved slowly towards the ground and the the force torque sensor readings are used to detect contact.
GuardedMove | |
---|---|
Goal |
Point start Point normal float32 search_distance |
Feedback | Point current |
Result |
Point final bool success |
Client Script | guarded_move.py |
NOTE In general this action is replaced by ArmFindSurface, however PLEXIL plans still rely on GuardedMove to find the ground position. Eventually, the plans will be updated to get this information through ArmFindSurface, which supports all the functionality of GuardedMove, and more.
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 direction in the sky using either pan/tilt joint positions or Cartesian space coordinates.
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 Action SetLightIntensity.
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. Exposure can additionally be set with
the ROS Action CameraSetExposure.
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
Both pan and tilt joint positions for the antenna mast system are broadcast on
the /pan_tilt_position
topic as a float64 array of length 2. The 1st value
in the array is the pan position and the 2nd value is the tilt position. Both
are represented in radians.
Uplink/downlink data to/from Earth for some duration in seconds. The antenna
will draw 9.6 Watts by default while active. This value can be changed in the
ow_power_system/config/system.cfg
under the name power_active_comms
.
NOTE: There is no simulation of mission to Earth communications. This
action simply simulates the power draw of uplinking and downlinking.
ActivateComms | |
---|---|
Goal | float64 duration |
Feedback | none |
Result | none |
Client Script | activate_comms.py |
Capture images with both antenna mast cameras.
CameraCapture | |
---|---|
Goal | none |
Feedback | none |
Result | none |
Client Script | camera_capture.py |
Set camera exposure level. automatic
is there only for OWLAT, and does
nothing in OceanWATERS because exposure must be set manually. If the provided
value for exposure
is equal to or less than 0 the current exposure setting
will be retained.
CameraSetExposure | |
---|---|
Goal |
bool automatic float64 exposure |
Feedback | none |
Result | none |
Client Script | camera_set_exposure.py |
Set intensity of either antenna mast spotlights. name
can be either "left" or
"right", corresponding to the left and right spotlights. intensity
must be
between 0 and 1, 1 being the brightest setting.
LightSetIntensity | |
---|---|
Goal |
string name float64 intensity |
Feedback | none |
Result |
bool success string message |
Client Script | light_set_intensity.py |
Pan and tilt lander's antenna mast to point stereo-cameras at a point in space.
frame
selects in which reference frame point
will be interpreted.
PanTiltMoveCartesian | |
---|---|
Goal |
int32 frame Point point |
Feedback | none |
Result | none |
Client Script | pan_tilt_move_cartesian.py |
Pan and tilt lander's antenna mast to provided pan and tilt joint positions.
PanTiltMoveJoints | |
---|---|
Goal |
float64 pan float64 tilt |
Feedback |
float64 pan_position float64 tilt_position |
Result |
float64 pan_position float64 tilt_position |
Client Script | pan_tilt_move_joints.py |
Change only the pan position of antenna mast.
Pan | |
---|---|
Goal | float64 pan |
Feedback | float64 pan_position |
Result | float64 pan_position |
Client Script | pan.py |
Change only the tilt position of antenna mast.
Tilt | |
---|---|
Goal | float64 tilt |
Feedback | float64 tilt_position |
Result | float64 tilt_position |
Client Script | tilt.py |
Here we list all other activities the lander can do and can be invoked via ROS Action calls.
Ingest material present in the sample dock. If no sample is present,
the sample_ingested
Result parameter will be False.
DockIngestSample | |
---|---|
Goal | none |
Feedback | none |
Result | bool sample_ingested |
Client Script | dock_ingest_sample.py |
NOTE This action is not necessary if the default fault behavior of
auto_clear_goal_errors
is true. If that setting is turned off, this action
is required before further actions can be called for that subsystem.
When a system fault occurs of type goal error
Fault Injection and Modeling,
it must be cleared before further operations can be performed by the subsystem
which incurred the error. The FaultClear
action can be used to clear the four
different types of goal errors that may occur, which are: Arm, Task, Camera,
and PanTilt.
FaultClear | |
---|---|
Goal | uint64 fault |
Feedback | none |
Result | none |
Client Script | fault_clear.py |
The goal error flags are published on the /system_faults_status
topic. The
different goal error flag values and their associated goal error category are
listed in the following table.
Flag Value | Goal Error Type |
---|---|
2 | Arm |
8 | Task |
16 | Camera |
64 | PanTilt |
Only these values will be accepted by this action.
Deliver samples present in the scoop end-effector to the sample dock.
TaskDeliverSample | |
---|---|
Goal | none |
Feedback | none |
Result | none |
Client Script | task_deliver_sample.py |
Sample in the scoop end-effector can be discarded if it is of no scientific
value. The discard action dumps the contents of the scoop somewhere above a
discard point on the terrain indicated by point
. If relative
is false, the
value of point
will be interpreted as an absolute position in the selected
frame. If relative
is true, point
will be interpreted as relative to the
current end-effector position in the selected frame. height
is the distance
above the discard point the scoop will position itself for the dump.
TaskDiscardSample | |
---|---|
Name | |
Goal |
int32 frame bool relative Point point float64 height |
Feedback | none |
Result | none |
Client Script | task_discard_sample.py |
The grinder end-effector is used to process hard surface material into tailings
that can be then be removed with a scoop task for delivery or discard. x_start
and y_start
are the x and y position on the terrain where the center of the
resulting trench will be, hereon known as the dig point. If parallel
is
true, the length of the trench will be parallel to a vector that connects the
lander base to the dig point. If parallel
is false, the length of the trench
will be perpendicular to that same vector. length
is length of the resulting
trench in meters.
TaskGrind | |
---|---|
Goal |
float32 x_start float32 y_start float32 depth float32 length bool parallel float32 ground_position |
Feedback | Point current |
Result | Point final |
Client Script | task_grind.py |
NOTE Currently TaskGrind is using a legacy-style action interface. There
are pending changes to be made to its Goal, Feedback, and Result definitions
that will make it them more similar in format to commands like
TaskScoopCircular. This is also the reason why the argument x_start
and
y_start
are misnomers.
The scoop end-effector is used to excavate tailings left over from a grind task
using a circular motion. The value of point
indicates the center of the
resulting trench on the terrain's surface, and is known as the dig point.
If relative
is false, the value of point
will be interpreted as an absolute
position in the selected frame. If relative
is true, the value of point
will
be interpreted as relative to the current end-effector position in the selected
frame. If parallel
is true, the scoop will dig facing away from the lander in
a direction parallel to the vector that connects the lander base to the
dig point. If parallel
is false, the scoop will dig in a direction
perpendicular to that vector.
TaskScoopCircular | |
---|---|
Goal |
int32 frame bool relative Point point float64 depth bool parallel |
Feedback | none |
Result | none |
Client Script | task_scoop_circular.py |
The scoop end-effector is used to excavate tailings left over from a grind task
using circular motions to enter and exit the terrain and a linear motion in
between. The value of point
indicates the center of the resulting trench on
the terrain's surface, and is known as the dig point. If relative
is false,
the value of point
will be interpreted as an absolute position in the selected
frame. If relative
is true, the value of point
will be interpreted as
relative to the current end-effector position in the selected frame. If
parallel
is true, the scoop will dig facing away from the lander in a
direction parallel to the vector that connects the lander base to the
dig point. If parallel
is false, the scoop will dig in a direction
perpendicular to that vector. length
is the distance in meters between the
end of the circular entry trajectory, and the beginning of the circular exit
trajectory.
TaskScoopLinear | |
---|---|
Goal |
int32 frame bool relative Point point float64 depth float64 length |
Feedback | none |
Result | none |
Client Script | task_scoop_linear.py |
Figure 4. Diagram of the power system for Release 13.
The lander is powered by a set of non-rechargeable lithium-ion battery packs to perform all its operations. In the envisioned operational environment, the battery pack would be 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.
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 most recent SOC, RUL, and
temperature values output by GSAP are published on ROS topics based on
the rate of the primary loop within the power system (default 1Hz).
See [Daigle2013] for additional details.
The power system utilizes a multi-cell battery model, managing
multiple predictions from multiple GSAP prognosers at once. GSAP is
set to run predictions for a 6S1P (6 series 1 parallel) battery model
and 4 such batteries are connected in parallel. Respective prognosers
are needed to simulate the 25V battery pack. As GSAP asynchronously
returns predictions from each of the instantiated prognosers, these
predictions are organized and published to other components in the
lander. The power system handles this by initializing every prognoser
and an associated PrognoserInputHandler
instance, then executing a
loop where these handlers generate input data (power draw, voltage, &
temperature) that is sent to its respective prognoser via a message
bus. When a prognoser receives input data, a new prediction is
triggered if one was not already running, and this prediction is
eventually generated and returned to the power system via the same
message bus. If a prediction was already underway when input is
received, it is used to update the state estimation step of the
process. See GSAP's GitHub Wiki
for more details.
While multiple GSAP prognosers are needed to run a full simulation of the
battery, this also applies a heavy additional load on the CPU for each
prognoser. Since users may not always be running the simulation with the
intention of running battery tests, this feature is largely disabled by default.
Only one prognoser will actively run during the simulation and acts as a sample
reading of the full battery, which should not affect overall battery
publications or status. To enable full battery simulation, see the settings
in the configuration file ow_power_system/config/system.cfg
.
Power consumed by lander operations is estimated in three ways.
-
A mechanical to electrochemical power conversion model is applied to joint telemetry (specifically
/joint_states/effort
) to model the power consumption of arm and antenna movements. -
A set of baseline power draws are defined for subsystems not otherwise modeled in OceanWATERS but likely present on the envisioned planetary lander: heating, science instruments, sample handling facilities, camera controller, computing, and other miscellaneous systems. These draws are specified in a configuration file (
ow_simulator/ow_power_system/config/system.cfg
) and can be user-tailored. Note that these power draws are continuously applied during the simulation and cannot be turned off. -
A set of "active-only" power draws are applied when the following components are turned on: lander lights (intensity-dependent), camera (trigger), communications. Note that communications are otherwise stubbed and only a fixed power draw is applied for the duration of the uplink or downlink. These power draw values are also specified in the configuration file given in (2).
A large variety of faults may be injected to simulate power system failures or operations in battery-constrained situations. See the Fault Injection and Modeling chapter of this user guide for details.
The power system model is implemented in a single ROS node defined in
the ow_power_system
ROS package. The main loop in this node
maintains the most recent predictions from each of the prognosers, and
once per cycle it publishes three topics based on this information:
ROS topic | Units | Description |
---|---|---|
/battery_state_of_charge |
n/a | Median estimation of the current battery voltage level, taken as the minimum of all prognoser predictions. 1 is a full battery and 0 is a depleted battery. |
/battery_remaining_useful_life |
seconds | The current median prediction for time left until the end of discharge, taken as the minimum of all prognoser predictions. |
/battery_temperature |
Celsius | The current best estimate of battery temperature, taken as the maximum of all prognoser predictions. |
The topics are published at a constant rate, even if the prognosers do not return predictions at the same consistency.
The different subsystems on-board the OceanWATERS lander can be commanded via ROS Actions. The activities and their associated action client scripts are listed in the following tables.
Arm Activities | Description | ROS Action Client (found in ow_lander/scripts ) |
---|---|---|
ArmMoveCartesian | Move end-effector to pose. | arm_move_cartesian.py |
ArmMoveCartesianGuarded | Move end-effector to pose; stop for resistance. | arm_move_cartesian_guarded.py |
ArmMoveJoint | Set position of a joint in the arm. | arm_move_joint.py |
ArmMoveJoints | Move arm to a configuration of joint positions. | arm_move_joints.py |
ArmMoveJointsGuarded | Move arm to a configuration of joint positions; stop for resistance. | arm_move_joints_guarded.py |
ArmFindSurface | Poke surface with the end-effector. | arm_find_surface.py |
ArmStop | Cease arm movement and abort arm action. | arm_stop.py |
ArmStow | Move arm to the stowed configuration. | arm_stow.py |
ArmUnstow | Move arm to the unstowed configuration. | arm_unstow.py |
GuardedMove | Deprecated version of ArmFindSurface. | guarded_move.py |
Antenna Mast Activities | Description | ROS Action Client (found in ow_lander/scripts ) |
---|---|---|
ActivateComms | Uplink/downlink data to/from Earth. | activate_comms.py |
CameraCapture | Capture images with both antenna mast cameras. | camera_capture.py |
CameraSetExposure | Set exposure level of both antenna mast cameras. | camera_set_exposure.py |
LightSetIntensity | Set intensity of either antenna mast spotlight. | light_set_intensity.py |
PanTiltMoveCartesian | Pan and tilt antenna mast to look at a point in space. | pan_tilt_move_cartesian.py |
PanTiltMoveJoints | Pan and tilt antenna mast to provided pan and tilt joint positions. | pan_tilt_move_joints.py |
Pan | Change only the pan position of antenna mast. | pan.py |
Tilt | Change only the tilt position of antenna mast. | tilt.py |
Lander Tasks | Description | ROS Action Client (found in ow_lander/scripts ) |
---|---|---|
DockIngestSample | Ingests sample contained inside the sample dock. | dock_ingest_sample.py |
FaultClear | Clear a goal error fault. | fault_clear.py |
TaskDeliverSample | Deliver sample present in the scoop to sample dock. | task_deliver_sample.py |
TaskDiscardSample | Discard sample present in the scoop above some point on the surface. | task_discard_sample.py |
TaskGrind | Process hard surface material into tailings. | task_grind.py |
TaskScoopCircular | Clear out tailings using a circular scooping motion. | task_scoop_circular.py |
TaskScoopLinear | Clear out tailings using a linear scooping motion. | task_scoop_linear.py |
For those activities or tasks that support the frame
parameter, the
following is a table of the allowed frames. In the accompanying
diagrams, the 🔴red🔴 rod is the x-axis, the 🟢green🟢 rod is the
y-axis, and the 🔵blue🔵 rod is the z-axis.
Gazebo Frame | Index | Description | Diagram |
---|---|---|---|
base_link |
0 | Center bottom of lander. Does not move. | |
l_scoop_tip |
1 | Tip of scoop blade. Moves with scoop. |
[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.