Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
towr Namespace Reference

Namespaces

 id
 

Classes

class  AnymalDynamicModel
 
class  AnymalKinematicModel
 
class  BaseMotionConstraint
 
struct  BaseState
 
class  BipedDynamicModel
 
class  BipedGaitGenerator
 
class  BipedKinematicModel
 
class  Block
 
class  Chimney
 
class  ChimneyLR
 
class  CubicHermitePolynomial
 
class  DynamicConstraint
 
class  DynamicModel
 
class  EulerConverter
 
class  FlatGround
 
class  ForceConstraint
 
class  GaitGenerator
 
class  Gap
 
class  HeightMap
 
class  HyqDynamicModel
 
class  HyqKinematicModel
 
class  KinematicModel
 
class  LinearEqualityConstraint
 
class  MonopedDynamicModel
 
class  MonopedGaitGenerator
 
class  MonopedKinematicModel
 
class  NlpFormulation
 
class  Node
 
class  NodeCost
 
class  NodesObserver
 
class  NodeSpline
 
class  NodesVariables
 
class  NodesVariablesAll
 
class  NodesVariablesEEForce
 
class  NodesVariablesEEMotion
 
class  NodesVariablesPhaseBased
 
class  Parameters
 
class  PhaseDurations
 
class  PhaseDurationsObserver
 
class  PhaseSpline
 
class  Polynomial
 
class  QuadrupedGaitGenerator
 
class  RangeOfMotionConstraint
 
struct  RobotModel
 
class  SingleRigidBodyDynamics
 
class  Slope
 
class  SoftConstraint
 
class  Spline
 
class  SplineAccConstraint
 
struct  SplineHolder
 
class  Stairs
 
class  State
 
class  SwingConstraint
 
class  TerrainConstraint
 
class  TimeDiscretizationConstraint
 
class  TotalDurationConstraint
 
class  TowrRosApp
 An example application of using TOWR together with ROS. More...
 
class  TowrRosInterface
 Base class to interface TOWR with a ROS GUI and RVIZ. More...
 
class  TowrUserInterface
 Translates user input into the ROS message TowrCommand.msg. More...
 

Typedefs

typedef Eigen::VectorXd VectorXd
 

Enumerations

enum  BipedIDs
 
enum  Dim2D
 
enum  Dim3D
 
enum  Dim6D
 
enum  Dx
 
enum  QuadrupedIDs
 
enum  YCursorRows {
  HEADING =6, OPTIMIZE =8, VISUALIZE, INITIALIZATION,
  PLOT, REPLAY_SPEED, GOAL_POS, GOAL_ORI,
  ROBOT, GAIT, OPTIMIZE_GAIT, TERRAIN,
  DURATION, CLOSE, END
}
 

Functions

static Eigen::Matrix3d BuildInertiaTensor (double Ixx, double Iyy, double Izz, double Ixy, double Ixz, double Iyz)
 
std::vector< NodesVariablesPhaseBased::PolyInfoBuildPolyInfos (int phase_count, bool first_phase_constant, int n_polys_in_changing_phase)
 
SingleRigidBodyDynamics::Jac Cross (const Eigen::Vector3d &in)
 
 TEST (DynamicModelTest, GetBaseAcceleration)
 
 TEST (DynamicConstraintTest, UpdateConstraintValues)
 
 TEST (DynamicModelTest, TestRotations)
 
 TEST (DynamicModelTest, GetJacobianOfAccWrtBase)
 
static Dim2D To2D (Dim3D dim)
 
static xpp::StateLinXd ToXpp (const towr::State &towr)
 
static std::pair< xpp::EndeffectorID, std::string > ToXppEndeffector (int number_of_ee, int towr_ee_id)
 
void UserCommandCallback (const towr_ros::TowrCommand &msg_in)
 

Variables

static const Dim6D AllDim6D []
 
 AX
 
 AY
 
 AZ
 
static std::map< towr::BipedIDs, std::string > biped_to_name
 
static std::map< towr::BipedIDs, xpp::biped::FootIDsbiped_to_xpp_id
 
static constexpr int k2D
 
static constexpr int k3D
 
static constexpr int k6D
 
 kAcc
 
 kJerk
 
 kPos
 
 kVel
 
 L
 
 LF
 
 LH
 
 LX
 
 LY
 
 LZ
 
static std::map< towr::QuadrupedIDs, std::string > quad_to_name
 
static std::map< towr::QuadrupedIDs, xpp::quad::FootIDsquad_to_xpp_id
 
 R
 
 RF
 
 RH
 
static const std::map< RobotModel::Robot, std::string > robot_names
 
static ros::Publisher rviz_pub
 
static ros::Publisher rviz_pub
 
static const std::map< HeightMap::TerrainID, std::string > terrain_names
 
 X
 
 X_
 
static constexpr int X_DESCRIPTION = 10
 
static constexpr int X_KEY = 1
 
static constexpr int X_VALUE = 35
 
 Y
 
 Y_
 
static constexpr int Y_STATUS = END+1
 
 Z
 

Enumeration Type Documentation

Enumerator
HEADING 
OPTIMIZE 
VISUALIZE 
INITIALIZATION 
PLOT 
REPLAY_SPEED 
GOAL_POS 
GOAL_ORI 
ROBOT 
GAIT 
OPTIMIZE_GAIT 
TERRAIN 
DURATION 
CLOSE 
END 

Definition at line 46 of file towr_user_interface.cc.

Function Documentation

static xpp::StateLinXd towr::ToXpp ( const towr::State towr)
static

Converts class "State" between two domains (have same internal representation).

Definition at line 118 of file towr_xpp_ee_map.h.

static std::pair<xpp::EndeffectorID, std::string> towr::ToXppEndeffector ( int  number_of_ee,
int  towr_ee_id 
)
static

Converts endeffector IDs of towr into the corresponding number used in xpp.

Parameters
number_of_eeNumber of endeffectors of current robot model.
towr_ee_idInteger used to represent the endeffector inside towr.
Returns
corresponding endeffector and string name in the xpp domain.

Definition at line 86 of file towr_xpp_ee_map.h.

void towr::UserCommandCallback ( const towr_ros::TowrCommand &  msg_in)

Definition at line 44 of file goal_pose_publisher.cc.

Variable Documentation

std::map<towr::BipedIDs, std::string> towr::biped_to_name
static
Initial value:
=
{
{L, "Left" },
{R, "Right"}
}
L
R

Mapping endeffector names

Definition at line 62 of file towr_xpp_ee_map.h.

std::map<towr::BipedIDs, xpp::biped::FootIDs> towr::biped_to_xpp_id
static
Initial value:

Mapping endeffector IDs

Definition at line 46 of file towr_xpp_ee_map.h.

std::map<towr::QuadrupedIDs, std::string> towr::quad_to_name
static
Initial value:
=
{
{LF, "Left-Front" },
{RF, "Right-Front"},
{LH, "Left-Hind" },
{RH, "Right-Hind" }
}
LF
LH
RH
RF

Definition at line 68 of file towr_xpp_ee_map.h.

std::map<towr::QuadrupedIDs, xpp::quad::FootIDs> towr::quad_to_xpp_id
static
Initial value:

Definition at line 52 of file towr_xpp_ee_map.h.

ros::Publisher towr::rviz_pub
static

Definition at line 42 of file rviz_terrain_publisher.cc.

ros::Publisher towr::rviz_pub
static

Definition at line 42 of file goal_pose_publisher.cc.

constexpr int towr::X_DESCRIPTION = 10
static

Definition at line 51 of file towr_user_interface.cc.

constexpr int towr::X_KEY = 1
static

Definition at line 50 of file towr_user_interface.cc.

constexpr int towr::X_VALUE = 35
static

Definition at line 52 of file towr_user_interface.cc.

constexpr int towr::Y_STATUS = END+1
static

Definition at line 49 of file towr_user_interface.cc.



towr_ros
Author(s): Alexander W. Winkler
autogenerated on Fri Apr 2 2021 02:14:22