from movel_seirios_msgs.srv import StringTrigger, StringTriggerResponse # like setbool#include <movel_seirios_msgs/StringTrigger.h><depend>movel_seirios_msgs</depend>find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
movel_seirios_msgs
)#!/usr/bin/env python
import rospy
from movel_seirios_msgs.srv import StringTrigger, StringTriggerResponse # like setbool
from std_msgs.msg import Bool, UInt8
class Pytest:
def __init__(self):
print('starting test node')
self.node = rospy.init_node('python_test')
self.service_start = rospy.Service('/external_process/trigger_detecting', StringTrigger, self.start_handler)
self.service_stop = rospy.Service('/external_process/stop_detecting', StringTrigger, self.stop_handler)
# IGNORE dummy_publisher - just to simulate UI cancel topic
self.dummy_publisher = rospy.Publisher('/cancel_publish', Bool, queue_size=1)
self.topic_process_cancel = rospy.Subscriber('/cancel_publish', Bool, self.handle_publish_cancel)
self.client_status = rospy.Publisher('/external_process/client_status', UInt8, queue_size=1)
self.flag = True
def start_handler(self, req):
print('inside start handler')
start_msg = StringTriggerResponse()
start_msg.success = True
start_msg.message = 'starting detect'
self.flag = True
self.publish_client_status()
while(self.flag):
print('executing something')
rospy.sleep(1)
return start_msg # return must be [success, message format]
def stop_handler(self, req):
print('inside stop handler')
self.flag = False
print('stop handler called')
stop_msg = StringTriggerResponse()
stop_msg.success = False
stop_msg.message = 'stopping detect'
return stop_msg
# IGNORE if you are not using a topic to stop your code
def handle_publish_cancel(self, req):
print("inside publish cancel", req.data)
cancel_trigger = req.data
if(cancel_trigger):
print('executing cancel stuff') # replace print statement
# IGNORE if you are not using launch files
def publish_client_status(self):
print("publish client status called")
cstatus = UInt8()
#Dummy code
#Decide how do you determine if your launch file is successful
#And replace the if-else statement
if (self.flag == True):
cstatus.data = 2 # if start_handler successfully called, task is successful and return 2
else:
cstatus.data = 3 # else task not successful, return 3
self.client_status.publish(cstatus)
if __name__ == '__main__':
py_test = Pytest()
#py_test.publish_cancel()
rospy.spin()#include <ros/ros.h>
#include <std_msgs/Bool.h>
#include <std_msgs/UInt8.h>
#include <movel_seirios_msgs/StringTrigger.h>
class Cpptest {
private:
ros::ServiceServer service_start;
ros::ServiceServer service_stop;
ros::Publisher dummy_publisher;
ros::Subscriber topic_process_cancel;
ros::Publisher client_status;
bool flag;
public:
Cpptest(ros::NodeHandle *nh) {
service_start = nh->advertiseService("/external_package/triggering_detect_cpp", &Cpptest::start_handler, this);
service_stop = nh->advertiseService("/external_package/stopping_detect_cpp", &Cpptest::stop_handler, this);
// Ignore dummy_publisher - just to simulate ui cancel button
dummy_publisher = nh->advertise<std_msgs::Bool>("/cancel_publish_cpp", 10);
topic_process_cancel = nh->subscribe("/cancel_publish_cpp", 1, &Cpptest::handle_publish_cancel, this);
client_status = nh->advertise<std_msgs::UInt8>("/external_process/client_status_cpp", 10);
}
bool start_handler(movel_seirios_msgs::StringTrigger::Request &req, movel_seirios_msgs::StringTrigger::Response &res) {
std::cout << "inside start handler\n";
res.success = true;
res.message = "starting detect";
//std::cout << res << "\n";
flag = true;
publish_client_status();
std::cout << "start handler flag "<< flag << "\n";
return true;
}
bool stop_handler(movel_seirios_msgs::StringTrigger::Request &req, movel_seirios_msgs::StringTrigger::Response &res) {
std::cout << "inside stop handler\n";
res.success = false;
res.message = "stopping detect";
//std::cout << res << "\n";
flag = false;
std::cout << "stop handler flag "<< flag << "\n";
return true;
}
// Ignore this method if not subscribing to stop topic
void handle_publish_cancel(const std_msgs::Bool& msg) {
std::cout << "inside handle publish cancel\n";
bool cancel_trigger;
cancel_trigger = msg.data;
//std::cout << "published msg " << cancel_trigger << "\n";
if(cancel_trigger){
std::cout << "do canceling stuff. cancel_trigger: " << cancel_trigger << "\n";
}
}
// Ignore this method if not using launch
void publish_client_status() {
std::cout << "publish client status called\n";
std_msgs::UInt8 cstatus;
if(flag) {
cstatus.data = 2;
}
else {
cstatus.data = 3;
}
std::cout << "client status " << cstatus << "2 for success, 3 for fail \n";
client_status.publish(cstatus);
}
};
int main(int argc, char** argv) {
ros::init(argc, argv, "cpp_test");
ros::NodeHandle nh;
Cpptest cpp_test(&nh);
ros::spin();
return 0;
} watchdog_rate: 2.0
watchdog_timeout: 0
service_req: true
# Below 4 params are COMPULSORY if service_req is true
service_start: "/external_process/trigger_detecting"
service_start_msg: "" # Optional, may put blank string
service_stop: "/external_process/stop_detecting"
service_stop_msg: "" # Optional, may put blank string
launch_req: false
# Below 3 params COMPULSORY if launch_req is true
launch_package:
launch_file:
launch_nodes:
topic_cancel_req: true
# topic_process_cancel required if topic_cancel_req is true
topic_process_cancel: "external_process/cancel_publish"
client_status: # Required if launch_req true, optional otherwise plugins:
- {name: detecting, type: 10, class: 'external_process_handler::ExternalProcessHandler'}detecting:
watchdog_rate: 2.0
watchdog_timeout: 0
service_req: true
launch_req: false
service_start: "/external_process/trigger_detecting" #required if service_req is true
service_start_msg: "" #optional if there is any particular msg needs to sent or else empty string
service_stop: "/external_process/stop_detecting" #required if service_req is true
service_start_msg: "" #optional if there is any particular msg needs to sent or else empty string
#launch_package: "yocs_velocity_smoother" #required if launch_req is true
#launch_file: "standalone.launch" #required if launch_req is true
#launch_nodes: "/nodelet_manager /velocity_smoother" #required if launch_req is true
topic_cancel_req: true
topic_process_cancel: "external_process/cancel_publish"