33#include < rtt/plugin/Plugin.hpp>
44#include < rtt/plugin/ServicePlugin.hpp>
55#include < rtt/internal/GlobalService.hpp>
6+ #include < rtt/scripting/Scripting.hpp>
67
8+ #include < rtt_ros_msgs/Eval.h>
79#include < rtt_ros_msgs/RunScript.h>
810#include < rtt_ros_msgs/GetPeerList.h>
911
@@ -24,16 +26,23 @@ class ROSDeploymentService : public RTT::Service
2426
2527 ros::NodeHandle nh_;
2628
29+ ros::ServiceServer eval_service_;
2730 ros::ServiceServer run_script_service_;
2831 ros::ServiceServer get_peer_list_service_;
2932
33+ bool eval_cb (
34+ rtt_ros_msgs::Eval::Request& request,
35+ rtt_ros_msgs::Eval::Response& response);
36+
3037 bool run_script_cb (
3138 rtt_ros_msgs::RunScript::Request& request,
3239 rtt_ros_msgs::RunScript::Response& response);
3340
3441 bool get_peer_list_cb (
3542 rtt_ros_msgs::GetPeerList::Request& request,
3643 rtt_ros_msgs::GetPeerList::Response& response);
44+
45+ RTT::OperationCaller<bool (std::string const &)> eval_;
3746};
3847
3948
@@ -44,13 +53,25 @@ ROSDeploymentService::ROSDeploymentService(OCL::DeploymentComponent* deployer) :
4453{
4554 if (deployer_) {
4655 // Create services
56+ eval_service_ = nh_.advertiseService (" eval" ,&ROSDeploymentService::eval_cb,this );
4757 run_script_service_ = nh_.advertiseService (" run_script" ,&ROSDeploymentService::run_script_cb,this );
4858 get_peer_list_service_ = nh_.advertiseService (" get_peer_list" ,&ROSDeploymentService::get_peer_list_cb,this );
59+
60+ eval_ = deployer_->getProvider <RTT::Scripting>(" scripting" )->eval ;
4961 } else {
5062 RTT::log (RTT::Error) << " Attempted to load the rosdeployment service on a TaskContext which is not an OCL::DeploymentComponent. No ROS services will be advertised." << RTT::endlog ();
5163 }
5264}
5365
66+ bool ROSDeploymentService::eval_cb (
67+ rtt_ros_msgs::Eval::Request& request,
68+ rtt_ros_msgs::Eval::Response& response)
69+ {
70+ if (!eval_.ready ()) return false ;
71+ response.success = eval_ (request.code );
72+ return true ;
73+ }
74+
5475bool ROSDeploymentService::run_script_cb (
5576 rtt_ros_msgs::RunScript::Request& request,
5677 rtt_ros_msgs::RunScript::Response& response)
0 commit comments