Public Member Functions | Static Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
exotica::Server Class Reference

#include <server.h>

Inheritance diagram for exotica::Server:
Inheritance graph
[legend]

Public Member Functions

void GetModel (const std::string &path, robot_model::RobotModelPtr &model, const std::string &urdf="", const std::string &srdf="")
 Get robot model. More...
 
robot_model::RobotModelConstPtr GetModel (const std::string &path, const std::string &urdf="", const std::string &srdf="")
 Get robot model. More...
 
std::string GetName ()
 Get the name of ther server. More...
 
bool HasModel (const std::string &path)
 Check if a robot model exist. More...
 
virtual ~Server ()
 
- Public Member Functions inherited from exotica::Uncopyable
 Uncopyable ()=default
 
 ~Uncopyable ()=default
 

Static Public Member Functions

template<typename T , typename... Args>
static ros::Publisher Advertise (Args &&...args)
 
static void Destroy ()
 
static ros::NodeHandleGetNodeHandle ()
 
template<typename T >
static bool GetParam (const std::string &name, T &param)
 
static bool HasParam (const std::string &name)
 
static void InitRos (std::shared_ptr< ros::NodeHandle > nh, int numThreads=2)
 
static std::shared_ptr< ServerInstance ()
 Get the server. More...
 
static bool IsRos ()
 
static void SendTransform (const tf::StampedTransform &transform)
 
static void SendTransform (const std::vector< tf::StampedTransform > &transforms)
 
static void SendTransform (const geometry_msgs::TransformStamped &transform)
 
static void SendTransform (const std::vector< geometry_msgs::TransformStamped > &transforms)
 
template<typename T >
static ros::ServiceClient ServiceClient (const std::string &service_name, bool persistent=false)
 
template<typename T >
static void SetParam (const std::string &name, T &param)
 
template<typename T , typename... Args>
static ros::Subscriber Subscribe (Args &&...args)
 

Private Member Functions

robot_model::RobotModelPtr LoadModel (const std::string &name, const std::string &urdf="", const std::string &srdf="")
 
void operator= (Server const &)=delete
 
 Server ()
 
 Server (Server const &)=delete
 Make sure the singleton does not get copied. More...
 

Private Attributes

std::string name_
 The name of this server. More...
 
std::shared_ptr< RosNodenode_
 
std::map< std::string, robot_model::RobotModelPtr > robot_models_
 Robot model cache. More...
 

Static Private Attributes

static std::shared_ptr< Serversingleton_server_ = nullptr
 

Detailed Description

Definition at line 61 of file server.h.

Constructor & Destructor Documentation

exotica::Server::~Server ( )
virtual

Definition at line 53 of file server.cpp.

exotica::Server::Server ( )
private

Definition at line 49 of file server.cpp.

exotica::Server::Server ( Server const &  )
privatedelete

Make sure the singleton does not get copied.

Member Function Documentation

template<typename T , typename... Args>
static ros::Publisher exotica::Server::Advertise ( Args &&...  args)
inlinestatic

Definition at line 128 of file server.h.

void exotica::Server::Destroy ( )
static

Definition at line 57 of file server.cpp.

void exotica::Server::GetModel ( const std::string &  path,
robot_model::RobotModelPtr &  model,
const std::string &  urdf = "",
const std::string &  srdf = "" 
)

Get robot model.

Parameters
pathRobot model name
modelRobot model

Definition at line 128 of file server.cpp.

robot_model::RobotModelConstPtr exotica::Server::GetModel ( const std::string &  path,
const std::string &  urdf = "",
const std::string &  srdf = "" 
)

Get robot model.

Parameters
pathRobot model name
Returns
robot model

Definition at line 140 of file server.cpp.

std::string exotica::Server::GetName ( )

Get the name of ther server.

Returns
Server name

Definition at line 157 of file server.cpp.

static ros::NodeHandle& exotica::Server::GetNodeHandle ( )
inlinestatic

Definition at line 97 of file server.h.

template<typename T >
static bool exotica::Server::GetParam ( const std::string &  name,
T &  param 
)
inlinestatic

Definition at line 104 of file server.h.

bool exotica::Server::HasModel ( const std::string &  path)

Check if a robot model exist.

Parameters
pathRobot model name
Returns
True if exist, false otherwise

Definition at line 152 of file server.cpp.

static bool exotica::Server::HasParam ( const std::string &  name)
inlinestatic

Definition at line 115 of file server.h.

static void exotica::Server::InitRos ( std::shared_ptr< ros::NodeHandle nh,
int  numThreads = 2 
)
inlinestatic

Definition at line 91 of file server.h.

static std::shared_ptr<Server> exotica::Server::Instance ( void  )
inlinestatic

Get the server.

Definition at line 65 of file server.h.

static bool exotica::Server::IsRos ( )
inlinestatic

Definition at line 96 of file server.h.

robot_model::RobotModelPtr exotica::Server::LoadModel ( const std::string &  name,
const std::string &  urdf = "",
const std::string &  srdf = "" 
)
private

Definition at line 80 of file server.cpp.

void exotica::Server::operator= ( Server const &  )
privatedelete
static void exotica::Server::SendTransform ( const tf::StampedTransform transform)
inlinestatic

Definition at line 145 of file server.h.

static void exotica::Server::SendTransform ( const std::vector< tf::StampedTransform > &  transforms)
inlinestatic

Definition at line 151 of file server.h.

static void exotica::Server::SendTransform ( const geometry_msgs::TransformStamped &  transform)
inlinestatic

Definition at line 157 of file server.h.

static void exotica::Server::SendTransform ( const std::vector< geometry_msgs::TransformStamped > &  transforms)
inlinestatic

Definition at line 163 of file server.h.

template<typename T >
static ros::ServiceClient exotica::Server::ServiceClient ( const std::string &  service_name,
bool  persistent = false 
)
inlinestatic

Definition at line 140 of file server.h.

template<typename T >
static void exotica::Server::SetParam ( const std::string &  name,
T &  param 
)
inlinestatic

Definition at line 110 of file server.h.

template<typename T , typename... Args>
static ros::Subscriber exotica::Server::Subscribe ( Args &&...  args)
inlinestatic

Definition at line 134 of file server.h.

Member Data Documentation

std::string exotica::Server::name_
private

The name of this server.

Definition at line 180 of file server.h.

std::shared_ptr<RosNode> exotica::Server::node_
private

Definition at line 182 of file server.h.

std::map<std::string, robot_model::RobotModelPtr> exotica::Server::robot_models_
private

Robot model cache.

Definition at line 185 of file server.h.

exotica::ServerPtr exotica::Server::singleton_server_ = nullptr
staticprivate

Definition at line 173 of file server.h.


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


exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Sat Apr 10 2021 02:34:50