Public Types | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
towr::TowrRosInterface Class Referenceabstract

Base class to interface TOWR with a ROS GUI and RVIZ. More...

#include <towr_ros_interface.h>

Inheritance diagram for towr::TowrRosInterface:
Inheritance graph
[legend]

Public Types

using TowrCommandMsg = towr_ros::TowrCommand
 
using Vector3d = Eigen::Vector3d
 
using XppVec = std::vector< xpp::RobotStateCartesian >
 

Protected Member Functions

virtual Parameters GetTowrParameters (int n_ee, const TowrCommandMsg &msg) const =0
 Formulates the actual TOWR problem to be solved. More...
 
virtual void SetIpoptParameters (const TowrCommandMsg &msg)=0
 Sets the parameters of the nonlinear programming solver IPOPT. More...
 
virtual void SetTowrInitialState ()=0
 Sets the base state and end-effector position. More...
 
 TowrRosInterface ()
 
virtual ~TowrRosInterface ()=default
 

Protected Attributes

NlpFormulation formulation_
 the default formulation, can be adapted More...
 
ifopt::IpoptSolver::Ptr solver_
 NLP solver, could also use SNOPT. More...
 

Private Member Functions

xpp_msgs::RobotParameters BuildRobotParametersMsg (const RobotModel &model) const
 
virtual BaseState GetGoalState (const TowrCommandMsg &msg) const
 
std::vector< XppVecGetIntermediateSolutions ()
 
XppVec GetTrajectory () const
 
void PublishInitialState ()
 
void SaveOptimizationAsRosbag (const std::string &bag_name, const xpp_msgs::RobotParameters &robot_params, const TowrCommandMsg user_command_msg, bool include_iterations=false)
 
void SaveTrajectoryInRosbag (rosbag::Bag &, const std::vector< xpp::RobotStateCartesian > &traj, const std::string &topic) const
 
void UserCommandCallback (const TowrCommandMsg &msg)
 

Private Attributes

::ros::Publisher initial_state_pub_
 
ifopt::Problem nlp_
 the actual nonlinear program to be solved. More...
 
::ros::Publisher robot_parameters_pub_
 
SplineHolder solution
 the solution splines linked to the opt-variables. More...
 
::ros::Subscriber user_command_sub_
 
double visualization_dt_
 duration between two rviz visualization states. More...
 

Detailed Description

Base class to interface TOWR with a ROS GUI and RVIZ.

This is very convenient to change goal states or terrains on the fly and test how your formulation holds up. A sample application implementing this interface is TowrRosApp.

Definition at line 57 of file towr_ros_interface.h.

Member Typedef Documentation

using towr::TowrRosInterface::TowrCommandMsg = towr_ros::TowrCommand

Definition at line 60 of file towr_ros_interface.h.

using towr::TowrRosInterface::Vector3d = Eigen::Vector3d

Definition at line 61 of file towr_ros_interface.h.

Definition at line 59 of file towr_ros_interface.h.

Constructor & Destructor Documentation

towr::TowrRosInterface::TowrRosInterface ( )
protected

Definition at line 47 of file towr_ros_interface.cc.

virtual towr::TowrRosInterface::~TowrRosInterface ( )
protectedvirtualdefault

Member Function Documentation

xpp_msgs::RobotParameters towr::TowrRosInterface::BuildRobotParametersMsg ( const RobotModel model) const
private

Definition at line 200 of file towr_ros_interface.cc.

BaseState towr::TowrRosInterface::GetGoalState ( const TowrCommandMsg msg) const
privatevirtual

Definition at line 66 of file towr_ros_interface.cc.

std::vector< TowrRosInterface::XppVec > towr::TowrRosInterface::GetIntermediateSolutions ( )
private

Definition at line 152 of file towr_ros_interface.cc.

virtual Parameters towr::TowrRosInterface::GetTowrParameters ( int  n_ee,
const TowrCommandMsg msg 
) const
protectedpure virtual

Formulates the actual TOWR problem to be solved.

Parameters
msgUser message to adjust the parameters dynamically.

When formulating your own application, here you can set your specific set of constraints and variables.

Implemented in towr::TowrRosApp.

TowrRosInterface::XppVec towr::TowrRosInterface::GetTrajectory ( ) const
private

Definition at line 165 of file towr_ros_interface.cc.

void towr::TowrRosInterface::PublishInitialState ( )
private

Definition at line 134 of file towr_ros_interface.cc.

void towr::TowrRosInterface::SaveOptimizationAsRosbag ( const std::string &  bag_name,
const xpp_msgs::RobotParameters &  robot_params,
const TowrCommandMsg  user_command_msg,
bool  include_iterations = false 
)
private

Definition at line 220 of file towr_ros_interface.cc.

void towr::TowrRosInterface::SaveTrajectoryInRosbag ( rosbag::Bag bag,
const std::vector< xpp::RobotStateCartesian > &  traj,
const std::string &  topic 
) const
private

Definition at line 254 of file towr_ros_interface.cc.

virtual void towr::TowrRosInterface::SetIpoptParameters ( const TowrCommandMsg msg)
protectedpure virtual

Sets the parameters of the nonlinear programming solver IPOPT.

Parameters
msgUser message that can be used to change the parameters.

Implemented in towr::TowrRosApp.

virtual void towr::TowrRosInterface::SetTowrInitialState ( )
protectedpure virtual

Sets the base state and end-effector position.

Implemented in towr::TowrRosApp.

void towr::TowrRosInterface::UserCommandCallback ( const TowrCommandMsg msg)
private

Definition at line 78 of file towr_ros_interface.cc.

Member Data Documentation

NlpFormulation towr::TowrRosInterface::formulation_
protected

the default formulation, can be adapted

Definition at line 87 of file towr_ros_interface.h.

::ros::Publisher towr::TowrRosInterface::initial_state_pub_
private

Definition at line 96 of file towr_ros_interface.h.

ifopt::Problem towr::TowrRosInterface::nlp_
private

the actual nonlinear program to be solved.

Definition at line 92 of file towr_ros_interface.h.

::ros::Publisher towr::TowrRosInterface::robot_parameters_pub_
private

Definition at line 97 of file towr_ros_interface.h.

SplineHolder towr::TowrRosInterface::solution
private

the solution splines linked to the opt-variables.

Definition at line 91 of file towr_ros_interface.h.

ifopt::IpoptSolver::Ptr towr::TowrRosInterface::solver_
protected

NLP solver, could also use SNOPT.

Definition at line 88 of file towr_ros_interface.h.

::ros::Subscriber towr::TowrRosInterface::user_command_sub_
private

Definition at line 95 of file towr_ros_interface.h.

double towr::TowrRosInterface::visualization_dt_
private

duration between two rviz visualization states.

Definition at line 93 of file towr_ros_interface.h.


The documentation for this class was generated from the following files:


towr_ros
Author(s): Alexander W. Winkler
autogenerated on Sat Apr 13 2019 02:28:05