#include <server.h>
|
| virtual | ~Server () |
| |
| bool | HasModel (const std::string &path) |
| | Check if a robot model exist. More...
|
| |
| 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...
|
| |
| | Uncopyable ()=default |
| |
| | ~Uncopyable ()=default |
| |
|
| static std::shared_ptr< Server > | Instance () |
| | Get the server. More...
|
| |
| static void | InitRos (std::shared_ptr< ros::NodeHandle > nh, int numThreads=2) |
| |
| static bool | IsRos () |
| |
| static ros::NodeHandle & | GetNodeHandle () |
| |
| template<typename T > |
| static bool | GetParam (const std::string &name, T ¶m) |
| |
| template<typename T > |
| static void | SetParam (const std::string &name, T ¶m) |
| |
| static bool | HasParam (const std::string &name) |
| |
| template<typename T , typename... Args> |
| static ros::Publisher | Advertise (Args &&... args) |
| |
| template<typename T , typename... Args> |
| static ros::Subscriber | Subscribe (Args &&... args) |
| |
| template<typename T > |
| static ros::ServiceClient | ServiceClient (const std::string &service_name, bool persistent=false) |
| |
| 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) |
| |
| static void | Destroy () |
| |
|
| | Server () |
| |
| | Server (Server const &)=delete |
| | Make sure the singleton does not get copied. More...
|
| |
| void | operator= (Server const &)=delete |
| |
| robot_model::RobotModelPtr | LoadModel (const std::string &name, const std::string &urdf="", const std::string &srdf="") |
| |
◆ ~Server()
| virtual exotica::Server::~Server |
( |
| ) |
|
|
virtual |
◆ Server() [1/2]
| exotica::Server::Server |
( |
| ) |
|
|
private |
◆ Server() [2/2]
| exotica::Server::Server |
( |
Server const & |
| ) |
|
|
privatedelete |
Make sure the singleton does not get copied.
◆ Advertise()
template<typename T , typename... Args>
| static ros::Publisher exotica::Server::Advertise |
( |
Args &&... |
args | ) |
|
|
inlinestatic |
◆ Destroy()
| static void exotica::Server::Destroy |
( |
| ) |
|
|
static |
◆ GetModel() [1/2]
| robot_model::RobotModelConstPtr exotica::Server::GetModel |
( |
const std::string & |
path, |
|
|
const std::string & |
urdf = "", |
|
|
const std::string & |
srdf = "" |
|
) |
| |
Get robot model.
- Parameters
-
- Returns
- robot model
◆ GetModel() [2/2]
| void exotica::Server::GetModel |
( |
const std::string & |
path, |
|
|
robot_model::RobotModelPtr & |
model, |
|
|
const std::string & |
urdf = "", |
|
|
const std::string & |
srdf = "" |
|
) |
| |
Get robot model.
- Parameters
-
| path | Robot model name |
| model | Robot model |
◆ GetName()
| std::string exotica::Server::GetName |
( |
| ) |
|
Get the name of ther server.
- Returns
- Server name
◆ GetNodeHandle()
| static ros::NodeHandle& exotica::Server::GetNodeHandle |
( |
| ) |
|
|
inlinestatic |
◆ GetParam()
template<typename T >
| static bool exotica::Server::GetParam |
( |
const std::string & |
name, |
|
|
T & |
param |
|
) |
| |
|
inlinestatic |
◆ HasModel()
| bool exotica::Server::HasModel |
( |
const std::string & |
path | ) |
|
Check if a robot model exist.
- Parameters
-
- Returns
- True if exist, false otherwise
◆ HasParam()
| static bool exotica::Server::HasParam |
( |
const std::string & |
name | ) |
|
|
inlinestatic |
◆ InitRos()
| static void exotica::Server::InitRos |
( |
std::shared_ptr< ros::NodeHandle > |
nh, |
|
|
int |
numThreads = 2 |
|
) |
| |
|
inlinestatic |
◆ Instance()
| static std::shared_ptr<Server> exotica::Server::Instance |
( |
| ) |
|
|
inlinestatic |
◆ IsRos()
| static bool exotica::Server::IsRos |
( |
| ) |
|
|
inlinestatic |
◆ LoadModel()
| robot_model::RobotModelPtr exotica::Server::LoadModel |
( |
const std::string & |
name, |
|
|
const std::string & |
urdf = "", |
|
|
const std::string & |
srdf = "" |
|
) |
| |
|
private |
◆ operator=()
| void exotica::Server::operator= |
( |
Server const & |
| ) |
|
|
privatedelete |
◆ SendTransform() [1/4]
| static void exotica::Server::SendTransform |
( |
const geometry_msgs::TransformStamped & |
transform | ) |
|
|
inlinestatic |
◆ SendTransform() [2/4]
| static void exotica::Server::SendTransform |
( |
const std::vector< geometry_msgs::TransformStamped > & |
transforms | ) |
|
|
inlinestatic |
◆ SendTransform() [3/4]
| static void exotica::Server::SendTransform |
( |
const std::vector< tf::StampedTransform > & |
transforms | ) |
|
|
inlinestatic |
◆ SendTransform() [4/4]
| static void exotica::Server::SendTransform |
( |
const tf::StampedTransform & |
transform | ) |
|
|
inlinestatic |
◆ ServiceClient()
template<typename T >
| static ros::ServiceClient exotica::Server::ServiceClient |
( |
const std::string & |
service_name, |
|
|
bool |
persistent = false |
|
) |
| |
|
inlinestatic |
◆ SetParam()
template<typename T >
| static void exotica::Server::SetParam |
( |
const std::string & |
name, |
|
|
T & |
param |
|
) |
| |
|
inlinestatic |
◆ Subscribe()
template<typename T , typename... Args>
| static ros::Subscriber exotica::Server::Subscribe |
( |
Args &&... |
args | ) |
|
|
inlinestatic |
◆ name_
| std::string exotica::Server::name_ |
|
private |
◆ node_
| std::shared_ptr<RosNode> exotica::Server::node_ |
|
private |
◆ robot_models_
| std::map<std::string, robot_model::RobotModelPtr> exotica::Server::robot_models_ |
|
private |
◆ singleton_server_
| std::shared_ptr<Server> exotica::Server::singleton_server_ |
|
staticprivate |
The documentation for this class was generated from the following file:
- /tmp/exotica/exotica_core/include/exotica_core/server.h