30 #ifndef EXOTICA_CORE_SERVER_H_
31 #define EXOTICA_CORE_SERVER_H_
36 #include <moveit/robot_model_loader/robot_model_loader.h>
38 #include <tf/transform_broadcaster.h>
49 RosNode(std::shared_ptr<ros::NodeHandle> nh,
int numThreads = 2);
52 inline tf::TransformBroadcaster &
GetTF() {
return tf_; }
55 std::shared_ptr<ros::NodeHandle>
nh_;
56 ros::AsyncSpinner
sp_;
57 tf::TransformBroadcaster
tf_;
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)
106 return Instance()->GetNodeHandle().getParam(name, param);
109 template <
typename T>
110 static void SetParam(
const std::string &name, T ¶m)
112 Instance()->GetNodeHandle().setParam(name, param);
115 inline bool static HasParam(
const std::string &name)
119 return Instance()->GetNodeHandle().hasParam(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>
140 static ros::ServiceClient
ServiceClient(
const std::string &service_name,
bool persistent =
false)
142 return Instance()->GetNodeHandle().serviceClient<T>(service_name, persistent);
148 Instance()->node_->GetTF().sendTransform(transform);
151 static void SendTransform(
const std::vector<tf::StampedTransform> &transforms)
154 Instance()->node_->GetTF().sendTransform(transforms);
160 Instance()->node_->GetTF().sendTransform(transform);
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_