delphyne
delphyne Namespace Reference

Namespaces

 behaviours
 
 blackboard
 
 cmdline
 
 common
 
 console
 
 detail
 
 roads
 
 trees
 
 utilities
 
 utility
 

Classes

class  AgentBase
 The most basic agent in Delphyne. More...
 
class  AgentBaseBlueprint
 The abstract blueprint class for agents in Delphyne. More...
 
struct  AgentBaseCollision
 A collision between any two AgentBase instances, along with the global coordinates of the point-of-collision. More...
 
class  AgentDiagramBuilder
 A builder that creates diagrams with inputs and outputs for agents. More...
 
class  AgentSimulationBase
 A runnable agent-based simulation, using Drake's system framework as its backbone. More...
 
class  AgentSimulationBaseBuilder
 A builder for agent-based simulations. More...
 
class  AgentState_v_Splitter
 A system that takes a AgentState_V and splits it into separate AgentState messages. More...
 
class  AngularRateAccelerationCommand
 Specializes BasicVector with specific getters and setters. More...
 
class  BasicTypedAgentBaseBlueprint
 A simplified abstract and typed blueprint for agents. More...
 
class  BicycleCar
 BicycleCar implements a nonlinear rigid body bicycle model from Althoff & Dolan (2014) [1]. More...
 
class  BicycleCarParameters
 Specializes BasicVector with specific getters and setters. More...
 
struct  BicycleCarParametersIndices
 Describes the row indices of a BicycleCarParameters. More...
 
class  BicycleCarState
 Specializes BasicVector with specific getters and setters. More...
 
struct  BicycleCarStateIndices
 Describes the row indices of a BicycleCarState. More...
 
class  BoxCarVis
 BoxCarVis displays a box as the visual representation of a vehicle. More...
 
class  CarVis
 CarVis is a base class that provides visualization geometries and their poses. More...
 
class  CarVisApplicator
 CarVisApplicator takes as input a PoseVector containing vehicle poses. More...
 
struct  ClosestPose
 ClosestPose bundles together the RoadOdometry of a particular target along with its distance measure relative to the ego vehicle. More...
 
class  Curve2
 Curve2 represents a path through two-dimensional Cartesian space. More...
 
class  DataLogger
 A class for simulation data logging. More...
 
class  DiagramBundle
 
class  DrakeDrivingCommandToIgn
 A system that translates Drake driving command messages to ignition driving command messages. More...
 
class  DrakeToIgn
 A system that translates Drake messages on its single input port (which will be discrete or abstract based on the type of the Drake message) to an ignition message on its single abstract output port. More...
 
class  DrivingCommand
 Specializes BasicVector with specific getters and setters. More...
 
struct  DrivingCommandIndices
 Describes the row indices of a DrivingCommand. More...
 
class  DrivingCommandMux
 A special-purpose multiplexer that packs two scalar inputs, steering angle (in units rad) and acceleration (in units m/s^2), into a vector-valued output of type DrivingCommand<T>, where the inputs feed directly through to the output. More...
 
class  DynamicBicycleCar
 DynamicBicycleCar implements a planar rigid body bicycle model of an automobile with a non-linear brush tire model from Bobier (2012) [1]. More...
 
class  DynamicBicycleCarInput
 Specializes BasicVector with specific getters and setters. More...
 
struct  DynamicBicycleCarInputIndices
 Describes the row indices of a DynamicBicycleCarInput. More...
 
class  DynamicBicycleCarParams
 Specializes BasicVector with specific getters and setters. More...
 
struct  DynamicBicycleCarParamsIndices
 Describes the row indices of a DynamicBicycleCarParams. More...
 
class  DynamicBicycleCarState
 Specializes BasicVector with specific getters and setters. More...
 
struct  DynamicBicycleCarStateIndices
 Describes the row indices of a DynamicBicycleCarState. More...
 
class  DynamicEnvironmentHandler
 Abstract API for managing the rules dynamic states of a maliput::api::RoadNetwork. More...
 
class  DynamicEnvironmentHandlerSystem
 
class  FixedPhaseIterationHandler
 DynamicEnvironmentHandler class implementation. More...
 
class  FramePoseAggregator
 A system that aggregates drake::systems::rendering::PoseVector inputs into a single drake::geometry::FramePoseVector output, each one associated to a specific frame ID. More...
 
class  IDMController
 IDMController implements the IDM (Intelligent Driver Model) planner, computed based only on the nearest car ahead. More...
 
class  IdmPlanner
 IdmPlanner implements the IDM (Intelligent Driver Model) equation governing longitudinal accelerations of a vehicle in single-lane traffic [1, 2]. More...
 
class  IdmPlannerParameters
 Specializes BasicVector with specific getters and setters. More...
 
struct  IdmPlannerParametersIndices
 Describes the row indices of a IdmPlannerParameters. More...
 
class  IgnCommandedPassThrough
 A pass through system with input u and output y = u that only redirects to the output when the commanded switch is true. More...
 
class  IgnDrivingCommandToDrake
 A system that translates ignition driving command messages to Drake driving command messages. More...
 
class  IgnModelsAssembler
 A helper System to assemble ignition::msgs::Model messages (given as an ignition::msgs::Model_V message i.e. More...
 
class  IgnModelsToIds
 Outputs the ids of the received ignition models. More...
 
class  IgnModelsTrafficLights
 System in charge of updating the traffic lights models according to the current value of the traffic lights state obtained through the maliput::api::RoadNetwork. More...
 
class  IgnModelVToIgnPoseV
 A system that translates ignition Model_V messages to ignition Pose_V messages messages. More...
 
class  IgnModelVToLcmViewerDraw
 A system that translates ignition Model_V messages to LCM viewer draw messages. More...
 
class  IgnPublisherSystem
 A system to publish ignition messages at its single abstract input port through an ignition transport topic. More...
 
class  IgnSubscriberSystem
 This class is the counterpart of Drake's LcmSubscriberSystem. More...
 
class  IgnToDrake
 A system that translates ignition messages on its single abstract input port to a Drake message on its single output port (which will be vector based or abstract depending on the type of the Drake message). More...
 
class  InteractiveSimulationStats
 A class that keeps statistics on a interactive simulation session An interactive session is usually composed of one or more simulation runs, depending on the interactions with the external world. More...
 
struct  LaneDirection
 LaneDirection holds the lane that a MaliputRailcar is traversing and the direction in which it is moving. More...
 
class  LcmViewerDrawToIgnModelV
 A system that translates LCM viewer draw messages to ignition Model_V. More...
 
class  LcmViewerLoadRobotToIgnModelV
 A system that translates LCM viewer load robot messages to ignition Model_V. More...
 
class  LoadRobotAggregator
 A system that aggregates LCM viewer load robot messages, creating a new viewer load robot message, with all of the links of the input messages. More...
 
class  MaliputRailcarState
 Specializes BasicVector with specific getters and setters. More...
 
struct  MaliputRailcarStateIndices
 Describes the row indices of a MaliputRailcarState. More...
 
class  MobilCarBlueprint
 An agent that follows roads as if they were railroad tracks. More...
 
class  MobilPlanner
 MOBIL (Minimizing Overall Braking Induced by Lane Changes) [1] is a planner that minimizes braking requirement for the ego car while also minimizing (per a weighting factor) the braking requirements of any trailing cars within the ego car's immediate neighborhood. More...
 
class  MobilPlannerParameters
 Specializes BasicVector with specific getters and setters. More...
 
struct  MobilPlannerParametersIndices
 Describes the row indices of a MobilPlannerParameters. More...
 
class  PoseBundleToAgentState_V
 A system that takes a PoseBundle and generates an array of AgentState (AgentState_V). More...
 
class  PoseVelocity
 Wraps the raw data contained in a trajectory expressed in terms of pose and velocity values. More...
 
class  PriusVis
 PriusVis displays a visualization of a 2015 Toyota Prius. More...
 
class  PurePursuit
 PurePursuit computes the required steering angle to achieve a goal point on an continuous planar path. More...
 
class  PurePursuitController
 PurePursuitController implements a pure pursuit controller. More...
 
class  PurePursuitParams
 Specializes BasicVector with specific getters and setters. More...
 
struct  PurePursuitParamsIndices
 Describes the row indices of a PurePursuitParams. More...
 
class  RailCar
 An agent that follows roads as if they were railroad tracks. More...
 
class  RailCarBlueprint
 An agent that follows roads as if they were railroad tracks. More...
 
class  RailFollower
 RailFollower models an entity that follows a maliput::api::Lane as if it were on rails and neglecting all physics. More...
 
class  RailFollowerParams
 Specializes BasicVector with specific getters and setters that specify the parameters used in updating a RailFollower system. More...
 
class  RailFollowerState
 Specializes BasicVector with specific getters and setters that specify the continuous state for a RailFollower system. More...
 
class  RightOfWaySystem
 RightOfWaySystem evaluates the current RightOfWayRule state that applies to the agent's location. More...
 
struct  RoadOdometry
 RoadOdometry contains the position of the vehicle with respect to a lane in a road, along with its velocity vector in the world frame. More...
 
class  RoadPath
 RoadPath converts a sequence of Maliput Lanes into a PiecewisePolynomial for the purpose of generating a path for a car to follow. More...
 
class  RuleRailCar
 An agent that follows roads as if they were railroad tracks. More...
 
class  RuleRailCarBlueprint
 An agent that follows roads as if they were railroad tracks. More...
 
class  SceneSystem
 A system that creates an ignition Scene message from three Model_V messages: one describing the geometry of the whole scene (which contains all the models, including their Visual subfield), another one with the updated poses for some of those models (the non-static ones) and the third one containing the updated visuals for some of those models. More...
 
class  SimpleCar2
 SimpleCar models an idealized response to driving commands, neglecting all physics. More...
 
class  SimpleCarBlueprint
 A very simple vehicle agent that can be teleoperated. More...
 
class  SimpleCarParams
 Specializes BasicVector with specific getters and setters. More...
 
struct  SimpleCarParamsIndices
 Describes the row indices of a SimpleCarParams. More...
 
class  SimpleCarState
 Specializes BasicVector with specific getters and setters. More...
 
struct  SimpleCarStateIndices
 Describes the row indices of a SimpleCarState. More...
 
class  SimpleCarStateTranslator
 Translates between LCM message objects and VectorBase objects for the SimpleCarState type. More...
 
class  SimplePowertrain
 SimplePowertrain models a powertrain with first-order lag. More...
 
class  SimplePriusVis
 Note: this class is based on (aka copy-of) the PriusVis class in Drake https://github.com/RobotLocomotion/drake/blob/master/automotive/prius_vis.h. More...
 
class  SimulationRunner
 A wrapper to execute the Drake simulator as a back-end. More...
 
class  SimulationRunStats
 A class that keeps statistics of a single simulation run. More...
 
class  SpeedSystem
 The SpeedSystem implements a very simple speed controller, taking as an input the current frame velocity (from an InputPort) and the desired speed (from a second InputPort), and producing an acceleration on an OutputPort to reach that speed. More...
 
class  TrafficPoseSelector
 TrafficPoseSelector is a class that provides the relevant pose or poses with respect to a given ego vehicle driving within a given maliput road geometry. More...
 
class  Trajectory
 A class that wraps a piecewise trajectory instantiated from pose data. More...
 
class  TrajectoryAgentBlueprint
 Trajectory following agents. More...
 
class  TrajectoryFollower
 TrajectoryFollower simply moves along a pre-established trajectory. More...
 
class  TranslateException
 
class  TypedAgentBaseBlueprint
 An abstract but typed blueprint class for agents in Delphyne. More...
 
class  UnicycleCar
 UnicylceCar is a parameter-free model of a car governed by the second-order equations. More...
 
class  UnicycleCarAgent
 An agent that follows roads as if they were railroad tracks. More...
 
class  UnicycleCarBlueprint
 A very simple vehicle agent with settable inputs. More...
 
class  VectorSource
 The VectorSource is a drake system to continually set an output port to a fixed value until the user decides to change it via the Set API. More...
 

Typedefs

using Agent = AgentBase< double >
 
using AutoDiffAgent = AgentBase< AutoDiff >
 
using SymbolicAgent = AgentBase< Symbolic >
 
using AgentBlueprint = AgentBaseBlueprint< double >
 
using AutoDiffAgentBlueprint = AgentBaseBlueprint< AutoDiff >
 
using SymbolicAgentBlueprint = AgentBaseBlueprint< Symbolic >
 
template<class A >
using TypedAgentBlueprint = TypedAgentBaseBlueprint< double, A >
 
template<class A >
using AutoDiffTypedAgentBlueprint = TypedAgentBaseBlueprint< AutoDiff, A >
 
template<class A >
using SymbolicTypedAgentBlueprint = TypedAgentBaseBlueprint< Symbolic, A >
 
template<class A >
using BasicTypedAgentBlueprint = BasicTypedAgentBaseBlueprint< double, A >
 
template<class A >
using BasicAutoDiffTypedAgentBlueprint = BasicTypedAgentBaseBlueprint< AutoDiff, A >
 
template<class A >
using BasicSymbolicTypedAgentBlueprint = BasicTypedAgentBaseBlueprint< Symbolic, A >
 
using BasicAgentBlueprint = BasicTypedAgentBaseBlueprint< double, AgentBase< double > >
 
using BasicAutoDiffAgentBlueprint = BasicTypedAgentBaseBlueprint< AutoDiff, AgentBase< AutoDiff > >
 
using BasicSymbolicAgentBlueprint = BasicTypedAgentBaseBlueprint< Symbolic, AgentBase< Symbolic > >
 
using AgentCollision = AgentBaseCollision< double >
 
using AutoDiffAgentCollision = AgentBaseCollision< AutoDiff >
 
using SymbolicAgentCollision = AgentBaseCollision< Symbolic >
 
using AgentSimulation = AgentSimulationBase< double >
 
using AutoDiffAgentSimulation = AgentSimulationBase< AutoDiff >
 
using SymbolicAgentSimulation = AgentSimulationBase< Symbolic >
 
using AutoDiff = ::drake::AutoDiffXd
 
using Symbolic = ::drake::symbolic::Expression
 
using Duration = std::chrono::duration< double >
 
using RealtimeClock = std::chrono::steady_clock
 
using TimePoint = std::chrono::time_point< RealtimeClock, Duration >
 
using AgentSimulationBuilder = AgentSimulationBaseBuilder< double >
 
using AutoDiffAgentSimulationBuilder = AgentSimulationBaseBuilder< AutoDiff >
 
using SymbolicAgentSimulationBuilder = AgentSimulationBaseBuilder< Symbolic >
 
template<class T >
using ProtobufIterator = google::protobuf::internal::RepeatedPtrIterator< T >
 
using DirectoryWalkFn = std::function< void(const std::string &path)>
 A function to recursively walk a directory. More...
 

Enumerations

enum  AheadOrBehind { kAhead = 0, kBehind = 1 }
 Specifies whether to assess the cars ahead or behind the ego car at its current orientation with respect to its lane. More...
 
enum  ScanStrategy { kBranches, kPath }
 Specifies whether to check ongoing lanes or both ongoing lanes and confluent branches for traffic. More...
 
enum  RoadPositionStrategy { kCache, kExhaustiveSearch }
 If kCache, configures a planning system (e.g. More...
 

Functions

drake::lcmt_viewer_load_robot BuildLoadMessageForRoad (const maliput::api::RoadGeometry &road_geometry, const maliput::utility::ObjFeatures &features)
 
drake::lcmt_viewer_load_robot BuildLoadMessageForTrafficLights (const std::vector< const maliput::api::rules::TrafficLight * > &traffic_lights)
 
template<typename T , typename std::enable_if< std::is_same< T, double >::value, int >::type = 0>
const drake::systems::InputPort< T > & WirePriusGeometry (const std::string &frame_root, drake::systems::DiagramBuilder< T > *builder, drake::geometry::SceneGraph< T > *scene_graph, std::set< drake::geometry::GeometryId > *geometry_ids)
 Wires up a Prius car geometry (and associated systems) using the given builder and scene_graph. More...
 
template<typename T >
drake::lcmt_viewer_load_robot BuildLoadMessage (const drake::geometry::SceneGraph< T > &scene_graph)
 
void WaitForShutdown ()
 Blocks the current thread until a SIGINT or SIGTERM is received. More...
 
template<typename T >
void CalcOngoingRoadPosition (const PoseVector< T > &pose, const FrameVelocity< T > &velocity, const RoadGeometry &road, RoadPosition *rp)
 
template void CalcOngoingRoadPosition (const PoseVector< drake::AutoDiffXd > &pose, const FrameVelocity< drake::AutoDiffXd > &velocity, const RoadGeometry &road, RoadPosition *rp)
 
template void CalcOngoingRoadPosition (const PoseVector< double > &pose, const FrameVelocity< double > &velocity, const RoadGeometry &road, RoadPosition *rp)
 
template<typename T >
void CalcOngoingRoadPosition (const drake::systems::rendering::PoseVector< T > &pose, const drake::systems::rendering::FrameVelocity< T > &velocity, const maliput::api::RoadGeometry &road, maliput::api::RoadPosition *rp)
 Given a PoseVector pose, find a car's current RoadGeometry via a search of immediate ongoing lanes, starting with the current one. More...
 
template<typename T >
calc_smooth_acceleration (const T &desired_acceleration, const T &max_velocity, const T &velocity_limit_kp, const T &current_velocity)
 Computes and returns an acceleration command that results in a smooth acceleration profile. More...
 
template double calc_smooth_acceleration< double > (const double &desired_acceleration, const double &current_velocity, const double &max_velocity, const double &velocity_limit_kp)
 
template AutoDiffXd calc_smooth_acceleration< AutoDiffXd > (const AutoDiffXd &desired_acceleration, const AutoDiffXd &current_velocity, const AutoDiffXd &max_velocity, const AutoDiffXd &velocity_limit_kp)
 
template Expression calc_smooth_acceleration< Expression > (const Expression &desired_acceleration, const Expression &current_velocity, const Expression &max_velocity, const Expression &velocity_limit_kp)
 
std::tuple< Curve2< double >, double, double > CreateTrajectoryParams (int index)
 Creates TrajectoryCar constructor demo arguments. More...
 
std::tuple< Curve2< double >, double, double > CreateTrajectoryParamsForDragway (const maliput::api::RoadGeometry &road_geometry, int index, double speed, double start_time)
 Creates TrajectoryCar constructor demo arguments for a vehicle on a dragway. More...
 
size_t GenerateLinkId (size_t robot_id, const std::string &link_name)
 Generates a unique ID for each pair of integer robot_id and link name as a string. More...
 
size_t GenerateVisualId (size_t robot_id, const std::string &link_name, size_t visual_id)
 Generates a unique ID for each group of integer robot_id, link name as a string, and visual id. More...
 
std::pair< int64_t, int64_t > MicrosToSecsAndNanos (int64_t micros)
 Converts from an integer value in microseconds to a pair of integers containing the value in seconds and the remainder of that in nanoseconds. More...
 
std::pair< int64_t, int64_t > MillisToSecsAndNanos (int64_t millis)
 Converts from an integer value in milliseconds to a pair of integers containing the value in seconds and the remainder of that in nanoseconds. More...
 
std::pair< int64_t, int64_t > SecsToSecsAndNanos (double time)
 Converts from a double value in seconds to a pair of integers containing the value in seconds and the remainder of that in nanoseconds. More...
 
double SecsAndNanosToMillis (int64_t secs, int64_t nsecs)
 Converts from a pair of integers containing independent time values in seconds and nanoseconds into a single double in milliseconds. More...
 
ignition::msgs::Time MillisToIgnitionTime (int64_t millis)
 Generates and returns an ignition::msgs::Time from a given integer value in milliseconds. More...
 
ignition::msgs::Time MicrosToIgnitionTime (int64_t micros)
 Generates and returns an ignition::msgs::Time from a given integer value in microseconds. More...
 
ignition::msgs::Time SecsToIgnitionTime (double secs)
 Generates and returns an ignition::msgs::Time from a given double value in seconds. More...
 
int64_t IgnitionTimeToMillis (const ignition::msgs::Time ign_time)
 Generates and returns an integer value in milliseconds. More...
 
void ZipDirectory (const std::string &source_path, const std::string &destination_path)
 Compresses the given srcpath directory content into the given destination_path archive recursively, using the zip format. More...
 
void UnzipDirectory (const std::string &archive_path, const std::string &extract_path)
 Decompresses a zip archive at archive_path into the given extract_path. More...
 
bool IsAbsolutePath (const std::string &path)
 Checks whether the given path is absolute or not. More...
 
bool IsValidFilepath (const std::string &path)
 Checks whether the given path is a valid file path (i.e. More...
 
std::string Dirname (const std::string &path)
 Extracts the directory name of the given path. More...
 
std::pair< std::string, std::string > SplitExtension (const std::string &path)
 Splits the given path into a (base path, extension) tuple, extension being the trailing characters preceded by the last dot '. More...
 
void WalkDirectory (const std::string &dirpath, const DirectoryWalkFn &walkfn, bool recursive)
 Walks the given dirpath in a top-down fashion. More...
 

Variables

static constexpr double kWeighFactor {0.95}
 
static constexpr int kIdmParamsIndex {0}
 
static constexpr int kPpParamsIndex {0}
 
static constexpr int kCarParamsIndex {1}
 

Typedef Documentation

◆ Agent

using Agent = AgentBase<double>

◆ AgentBlueprint

◆ AgentCollision

◆ AgentSimulation

◆ AgentSimulationBuilder

◆ AutoDiff

using AutoDiff = ::drake::AutoDiffXd

◆ AutoDiffAgent

◆ AutoDiffAgentBlueprint

◆ AutoDiffAgentCollision

◆ AutoDiffAgentSimulation

◆ AutoDiffAgentSimulationBuilder

◆ AutoDiffTypedAgentBlueprint

◆ BasicAgentBlueprint

◆ BasicAutoDiffAgentBlueprint

◆ BasicAutoDiffTypedAgentBlueprint

◆ BasicSymbolicAgentBlueprint

◆ BasicSymbolicTypedAgentBlueprint

◆ BasicTypedAgentBlueprint

◆ DirectoryWalkFn

using DirectoryWalkFn = std::function<void(const std::string& path)>

A function to recursively walk a directory.

Parameters
[in]pathFull path to found file or directory.
See also
WalkDirectory

◆ Duration

using Duration = std::chrono::duration<double>

◆ ProtobufIterator

using ProtobufIterator = google::protobuf::internal::RepeatedPtrIterator<T>

◆ RealtimeClock

using RealtimeClock = std::chrono::steady_clock

◆ Symbolic

using Symbolic = ::drake::symbolic::Expression

◆ SymbolicAgent

◆ SymbolicAgentBlueprint

◆ SymbolicAgentCollision

◆ SymbolicAgentSimulation

◆ SymbolicAgentSimulationBuilder

◆ SymbolicTypedAgentBlueprint

◆ TimePoint

using TimePoint = std::chrono::time_point<RealtimeClock, Duration>

◆ TypedAgentBlueprint

Enumeration Type Documentation

◆ AheadOrBehind

enum AheadOrBehind
strong

Specifies whether to assess the cars ahead or behind the ego car at its current orientation with respect to its lane.

Enumerator
kAhead 
kBehind 

◆ RoadPositionStrategy

enum RoadPositionStrategy
strong

If kCache, configures a planning system (e.g.

IdmController, MobilPlanner) to declare an abstract state that caches the last-computed RoadPosition. If kExhaustiveSearch, then the system will contain no abstract states. Note that the kCache option is for performance speedup (at the expense of optimizer compatibility) by preventing a potentially sizeable computation within RoadGeometry::ToRoadPosition().

Enumerator
kCache 
kExhaustiveSearch 

◆ ScanStrategy

enum ScanStrategy
strong

Specifies whether to check ongoing lanes or both ongoing lanes and confluent branches for traffic.

Enumerator
kBranches 
kPath 

Function Documentation

◆ BuildLoadMessage()

drake::lcmt_viewer_load_robot delphyne::BuildLoadMessage ( const drake::geometry::SceneGraph< T > &  scene_graph)

◆ BuildLoadMessageForRoad()

drake::lcmt_viewer_load_robot BuildLoadMessageForRoad ( const maliput::api::RoadGeometry road_geometry,
const maliput::utility::ObjFeatures features 
)

◆ BuildLoadMessageForTrafficLights()

drake::lcmt_viewer_load_robot BuildLoadMessageForTrafficLights ( const std::vector< const maliput::api::rules::TrafficLight * > &  traffic_lights)

◆ calc_smooth_acceleration()

T calc_smooth_acceleration ( const T &  desired_acceleration,
const T &  max_velocity,
const T &  velocity_limit_kp,
const T &  current_velocity 
)

Computes and returns an acceleration command that results in a smooth acceleration profile.

It is smooth in the sense that it looks pleasant and realistic, though it may not reflect the actual acceleration behavior of real vehicles.

For a given acceleration plan, all of the input parameters typically remain constant except for current_velocity.

Instantiated templates for the following ScalarTypes are provided:

  • double
  • drake::AutoDiffXd
  • drake::symbolic::Expression

They are already available to link against in the containing library.

◆ calc_smooth_acceleration< AutoDiffXd >()

template AutoDiffXd delphyne::calc_smooth_acceleration< AutoDiffXd > ( const AutoDiffXd &  desired_acceleration,
const AutoDiffXd &  current_velocity,
const AutoDiffXd &  max_velocity,
const AutoDiffXd &  velocity_limit_kp 
)

◆ calc_smooth_acceleration< double >()

template double delphyne::calc_smooth_acceleration< double > ( const double &  desired_acceleration,
const double &  current_velocity,
const double &  max_velocity,
const double &  velocity_limit_kp 
)

◆ calc_smooth_acceleration< Expression >()

template Expression delphyne::calc_smooth_acceleration< Expression > ( const Expression &  desired_acceleration,
const Expression &  current_velocity,
const Expression &  max_velocity,
const Expression &  velocity_limit_kp 
)

◆ CalcOngoingRoadPosition() [1/4]

void delphyne::CalcOngoingRoadPosition ( const drake::systems::rendering::PoseVector< T > &  pose,
const drake::systems::rendering::FrameVelocity< T > &  velocity,
const maliput::api::RoadGeometry road,
maliput::api::RoadPosition rp 
)

Given a PoseVector pose, find a car's current RoadGeometry via a search of immediate ongoing lanes, starting with the current one.

Uses the provided FrameVelocity velocity to determine which side of the lane (provided in rp) to check. Updates rp with the result, if one is found; otherwise updates rp using the result of a global search of the road.

Instantiated templates for the following scalar types T are provided:

  • double
  • drake::AutoDiffXd

They are already available to link against in the containing library.

◆ CalcOngoingRoadPosition() [2/4]

template void delphyne::CalcOngoingRoadPosition ( const PoseVector< double > &  pose,
const FrameVelocity< double > &  velocity,
const RoadGeometry road,
RoadPosition rp 
)

◆ CalcOngoingRoadPosition() [3/4]

template void delphyne::CalcOngoingRoadPosition ( const PoseVector< drake::AutoDiffXd > &  pose,
const FrameVelocity< drake::AutoDiffXd > &  velocity,
const RoadGeometry road,
RoadPosition rp 
)

◆ CalcOngoingRoadPosition() [4/4]

void delphyne::CalcOngoingRoadPosition ( const PoseVector< T > &  pose,
const FrameVelocity< T > &  velocity,
const RoadGeometry road,
RoadPosition rp 
)

◆ CreateTrajectoryParams()

std::tuple< Curve2< double >, double, double > CreateTrajectoryParams ( int  index)

Creates TrajectoryCar constructor demo arguments.

The details of the trajectory are not documented / promised by this API.

Parameters
indexSelects which pre-programmed trajectory to use.
Returns
tuple of curve, speed, start_time

◆ CreateTrajectoryParamsForDragway()

std::tuple< Curve2< double >, double, double > CreateTrajectoryParamsForDragway ( const maliput::api::RoadGeometry road_geometry,
int  index,
double  speed,
double  start_time 
)

Creates TrajectoryCar constructor demo arguments for a vehicle on a dragway.

The details of the trajectory are not documented / promised by this API.

Parameters
road_geometryThe dragway upon which the TrajectoryCar will travel.
indexThe lane index within the provided road_geometry.
speedThe speed of the vehicle.
start_timeThe time when the vehicle should start driving.
Returns
tuple of curve, speed, start_time

◆ Dirname()

std::string Dirname ( const std::string &  path)

Extracts the directory name of the given path.

Remarks
No actual filesystem lookups are performed during directory name extraction.
Parameters
[in]pathThe path to extract a directory name from.
Returns
The extracted directory name, if any.

◆ GenerateLinkId()

size_t delphyne::GenerateLinkId ( size_t  robot_id,
const std::string &  link_name 
)

Generates a unique ID for each pair of integer robot_id and link name as a string.

The values are serialized and concatenated into a single string and a hash of that string is returned.

Parameters
[in]robot_idAn integer value containing the robot index.
[in]link_nameThe name of the link, which must be unique to the robot_id.
Returns
a unique integer identifying the link.

◆ GenerateVisualId()

size_t delphyne::GenerateVisualId ( size_t  robot_id,
const std::string &  link_name,
size_t  visual_id 
)

Generates a unique ID for each group of integer robot_id, link name as a string, and visual id.

The values are serialized and concatenated into a single string and a hash of that string is returned.

Parameters
[in]robot_idAn integer value containing the robot index.
[in]link_nameThe name of the link, which must be unique to the robot_id.
[in]visual_idAn integer value of the visual index within the link.
Returns
a unique integer identifying the visual.

◆ IgnitionTimeToMillis()

int64_t IgnitionTimeToMillis ( const ignition::msgs::Time  ign_time)

Generates and returns an integer value in milliseconds.

Parameters
[in]ign_timean ignition messages Time object.
Returns
An integer value in milliseconds representing the total time contained in the ignition message.

◆ IsAbsolutePath()

bool IsAbsolutePath ( const std::string &  path)

Checks whether the given path is absolute or not.

◆ IsValidFilepath()

bool IsValidFilepath ( const std::string &  path)

Checks whether the given path is a valid file path (i.e.

no trailing slash, no dot references to the current directory or the parent directory).

◆ MicrosToIgnitionTime()

ignition::msgs::Time MicrosToIgnitionTime ( int64_t  micros)

Generates and returns an ignition::msgs::Time from a given integer value in microseconds.

Parameters
[in]microsAn integer value containing the time in microseconds.
Returns
An ignition messages Time value composed by the value in seconds and nanoseconds translated from the microseconds' input.

◆ MicrosToSecsAndNanos()

std::pair< int64_t, int64_t > MicrosToSecsAndNanos ( int64_t  micros)

Converts from an integer value in microseconds to a pair of integers containing the value in seconds and the remainder of that in nanoseconds.

Parameters
[in]microsAn integer value containing the time in microseconds.
Returns
A pair of integers containing the translated time value composed by seconds and nanoseconds.

◆ MillisToIgnitionTime()

ignition::msgs::Time MillisToIgnitionTime ( int64_t  millis)

Generates and returns an ignition::msgs::Time from a given integer value in milliseconds.

Parameters
[in]millisAn integer value containing the time in milliseconds.
Returns
An ignition messages Time value composed by the value in seconds and nanoseconds translated from the milliseconds' input.

◆ MillisToSecsAndNanos()

std::pair< int64_t, int64_t > MillisToSecsAndNanos ( int64_t  millis)

Converts from an integer value in milliseconds to a pair of integers containing the value in seconds and the remainder of that in nanoseconds.

Parameters
[in]millisAn integer value containing the time in milliseconds.
Returns
A pair of integers containing the translated time value composed by seconds and nanoseconds.

◆ SecsAndNanosToMillis()

double SecsAndNanosToMillis ( int64_t  secs,
int64_t  nsecs 
)

Converts from a pair of integers containing independent time values in seconds and nanoseconds into a single double in milliseconds.

Parameters
[in]secsAn integer value containing the time component in seconds to translate.
[in]nsecsAn integer value containing the time component in nanoseconds to translate.
Returns
A pair of integers containing the translated time value composed by seconds and nanoseconds.

◆ SecsToIgnitionTime()

ignition::msgs::Time SecsToIgnitionTime ( double  secs)

Generates and returns an ignition::msgs::Time from a given double value in seconds.

Parameters
[in]secsA double value containing the time in seconds.
Returns
An ignition messages Time value composed by the value in seconds and nanoseconds translated from the seconds' double input.

◆ SecsToSecsAndNanos()

std::pair< int64_t, int64_t > SecsToSecsAndNanos ( double  time)

Converts from a double value in seconds to a pair of integers containing the value in seconds and the remainder of that in nanoseconds.

Parameters
[in]timeA double containing the time to be translated in seconds.
Returns
A pair of integers containing the translated time value composed by seconds and nanoseconds.

◆ SplitExtension()

std::pair< std::string, std::string > SplitExtension ( const std::string &  path)

Splits the given path into a (base path, extension) tuple, extension being the trailing characters preceded by the last dot '.

' in the last portion of path. As an example, /tmp/./../home/file.0.txt would split into /tmp/./../home/file.0 and txt.

Parameters
[in]pathThe path to split.
Returns
A (base path, extension) tuple.

◆ UnzipDirectory()

void UnzipDirectory ( const std::string &  archive_path,
const std::string &  extract_path 
)

Decompresses a zip archive at archive_path into the given extract_path.

Exceptions
std::runtime_errorif archive_path is not a file.
std::runtime_errorif extract_path is not a directory.
std::runtime_errorif the unzipping process fails at any point.

◆ WaitForShutdown()

void WaitForShutdown ( )

Blocks the current thread until a SIGINT or SIGTERM is received.

Note that this function registers a signal handler. Do not use this function if you want to manage yourself SIGINT/SIGTERM.

◆ WalkDirectory()

void WalkDirectory ( const std::string &  dirpath,
const DirectoryWalkFn walkfn,
bool  recursive 
)

Walks the given dirpath in a top-down fashion.

Parameters
[in]dirpathPath to directory to be walked.
[in]walkfnCallable to walk found files and directories with.
[in]recursiveWhether to recursively walk inner directories or not.
Exceptions
std::runtime_errorif dirpath does not refer to an existing directory.

◆ WirePriusGeometry()

const drake::systems::InputPort<T>& delphyne::WirePriusGeometry ( const std::string &  frame_root,
drake::systems::DiagramBuilder< T > *  builder,
drake::geometry::SceneGraph< T > *  scene_graph,
std::set< drake::geometry::GeometryId > *  geometry_ids 
)

Wires up a Prius car geometry (and associated systems) using the given builder and scene_graph.

Parameters
frame_rootA root name (i.e. a prefix) for all Prius car frames.
builderThe builder used to wire associated systems into the diagram.
scene_graphThe scene graph where geometries are registered into.
geometry_idsOutput set of registered geometry IDs.
Returns
The Prius car drake::systems::rendering::PoseVector (abstract) port to update its pose (i.e. the pose of the whole care frame) in the world.
Template Parameters
TA valid Eigen scalar type.

◆ ZipDirectory()

void ZipDirectory ( const std::string &  source_path,
const std::string &  destination_path 
)

Compresses the given srcpath directory content into the given destination_path archive recursively, using the zip format.

All source_path parent directories are stripped from archive entry names if present.

Exceptions
std::runtime_errorif source_path is not an existing directory.
std::runtime_errorif destination_path already exists.
std::runtime_errorif the zipping process fails at any point.

Variable Documentation

◆ kCarParamsIndex

constexpr int kCarParamsIndex {1}
staticconstexpr

◆ kIdmParamsIndex

constexpr int kIdmParamsIndex {0}
staticconstexpr

◆ kPpParamsIndex

constexpr int kPpParamsIndex {0}
staticconstexpr

◆ kWeighFactor

constexpr double kWeighFactor {0.95}
staticconstexpr