Go to the documentation of this file.
30 #ifndef EXOTICA_CORE_SERVER_H_
31 #define EXOTICA_CORE_SERVER_H_
49 RosNode(std::shared_ptr<ros::NodeHandle> nh,
int numThreads = 2);
55 std::shared_ptr<ros::NodeHandle>
nh_;
75 bool HasModel(
const std::string &path);
80 void GetModel(
const std::string &path, robot_model::RobotModelPtr &model,
const std::string &
urdf =
"",
const std::string &
srdf =
"");
85 robot_model::RobotModelConstPtr
GetModel(
const std::string &path,
const std::string &
urdf =
"",
const std::string &
srdf =
"");
91 inline static void InitRos(std::shared_ptr<ros::NodeHandle> nh,
int numThreads = 2)
100 return Instance()->node_->GetNodeHandle();
103 template <
typename T>
104 static bool GetParam(
const std::string &name, T ¶m)
109 template <
typename T>
110 static void SetParam(
const std::string &name, T ¶m)
115 inline bool static HasParam(
const std::string &name)
127 template <
typename T,
typename... Args>
130 return Instance()->GetNodeHandle().advertise<T>(std::forward<Args>(
args)...);
133 template <
typename T,
typename... Args>
136 return Instance()->GetNodeHandle().subscribe<T>(std::forward<Args>(
args)...);
139 template <
typename T>
142 return Instance()->GetNodeHandle().serviceClient<T>(service_name, persistent);
151 static void SendTransform(
const std::vector<tf::StampedTransform> &transforms)
154 Instance()->node_->GetTF().sendTransform(transforms);
163 static void SendTransform(
const std::vector<geometry_msgs::TransformStamped> &transforms)
166 Instance()->node_->GetTF().sendTransform(transforms);
177 robot_model::RobotModelPtr
LoadModel(
const std::string &name,
const std::string &
urdf =
"",
const std::string &
srdf =
"");
191 #endif // EXOTICA_CORE_SERVER_H_
std::string GetName()
Get the name of ther server.
std::shared_ptr< ros::NodeHandle > nh_
std::string name_
The name of this server.
static bool GetParam(const std::string &name, T ¶m)
void operator=(Server const &)=delete
static std::shared_ptr< Server > Instance()
Get the server.
static void SendTransform(const tf::StampedTransform &transform)
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
static ros::Subscriber Subscribe(Args &&... args)
static void SendTransform(const std::vector< geometry_msgs::TransformStamped > &transforms)
static std::shared_ptr< Server > singleton_server_
bool HasModel(const std::string &path)
Check if a robot model exist.
std::map< std::string, robot_model::RobotModelPtr > robot_models_
Robot model cache.
static void InitRos(std::shared_ptr< ros::NodeHandle > nh, int numThreads=2)
void GetModel(const std::string &path, robot_model::RobotModelPtr &model, const std::string &urdf="", const std::string &srdf="")
Get robot model.
static bool HasParam(const std::string &name)
static ros::ServiceClient ServiceClient(const std::string &service_name, bool persistent=false)
std::shared_ptr< RosNode > node_
static void SetParam(const std::string &name, T ¶m)
static void SendTransform(const std::vector< tf::StampedTransform > &transforms)
ros::NodeHandle & GetNodeHandle()
std::shared_ptr< Server > ServerPtr
robot_model::RobotModelPtr LoadModel(const std::string &name, const std::string &urdf="", const std::string &srdf="")
T param(const std::string ¶m_name, const T &default_val)
tf::TransformBroadcaster & GetTF()
static ros::Publisher Advertise(Args &&... args)
tf::TransformBroadcaster tf_
static ros::NodeHandle & GetNodeHandle()
static void SendTransform(const geometry_msgs::TransformStamped &transform)
exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Fri Aug 2 2024 08:43:02