diff --git a/CMakeLists.txt b/CMakeLists.txt index 2223c66..9a2a582 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -50,18 +50,23 @@ find_package(catkin REQUIRED COMPONENTS ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) ## Generate messages in the 'msg' folder -# add_message_files( -# FILES -# Message1.msg -# Message2.msg -# ) + add_message_files( + FILES + PhoXiSize.msg + ) ## Generate services in the 'srv' folder -# add_service_files( -# FILES -# Service1.srv -# Service2.srv -# ) + add_service_files( + FILES + GetDeviceList.srv + ConnectCamera.srv + IsAcquiring.srv + GetFrame.srv + TriggerImage.srv + GetHardwareIdentification.srv + GetSupportedCapturingModes.srv + IsConnected.srv + ) ## Generate actions in the 'action' folder # add_action_files( @@ -71,10 +76,10 @@ find_package(catkin REQUIRED COMPONENTS # ) ## Generate added messages and services with any dependencies listed here -# generate_messages( -# DEPENDENCIES -# sensor_msgs# std_msgs -# ) + generate_messages( + DEPENDENCIES + sensor_msgs std_msgs + ) ################################################ ## Declare ROS dynamic reconfigure parameters ## @@ -111,7 +116,8 @@ generate_dynamic_reconfigure_options( ## DEPENDS: system dependencies of this project that dependent projects also need catkin_package( -# INCLUDE_DIRS include + CATKIN_DEPENDS message_runtime std_msgs sensor_msgs + # INCLUDE_DIRS include # LIBRARIES pho_driver # CATKIN_DEPENDS dynamic_reconfigure pcl_ros roscpp roslib rospy sensor_msgs std_msgs tf # DEPENDS system_lib @@ -178,6 +184,7 @@ add_dependencies(phoxi_camera_node ${PROJECT_NAME}_gencfg) # ${catkin_LIBRARIES} # ) +#message(${PHOXI_LIBRARY}) target_link_libraries(phoxi_camera_node debug ${catkin_LIBRARIES} optimized ${catkin_LIBRARIES} @@ -235,7 +242,12 @@ target_link_libraries(phoxi_camera_node ## Add folders to be run by python nosetests # catkin_add_nosetests(test) #add dynamic reconfigure api -#find_package(catkin REQUIRED dynamic_reconfigure) +find_package(catkin REQUIRED COMPONENTS + roscpp + rospy + std_msgs + message_generation + ) diff --git a/cfg/phoxi_camera.cfg b/cfg/phoxi_camera.cfg index e540117..390023e 100755 --- a/cfg/phoxi_camera.cfg +++ b/cfg/phoxi_camera.cfg @@ -5,17 +5,34 @@ from dynamic_reconfigure.parameter_generator_catkin import * gen = ParameterGenerator() -gen.add("int_param", int_t, 0, "An Integer parameter", 50, 0, 100) -gen.add("double_param", double_t, 0, "A double parameter", .5, 0, 1) -gen.add("str_param", str_t, 0, "A string parameter", "Hello World") -gen.add("bool_param", bool_t, 0, "A Boolean parameter", True) +gen.add("size_width", int_t, 1 << 1, "An Integer parameter", 1920, 0) +gen.add("size_height", int_t, 1 << 2, "An Integer parameter", 1080, 0) +gen.add("capturing_size_width", int_t, 1 << 3, "An Integer parameter", 1920, 0) +gen.add("capturing_size_height", int_t, 1 << 4, "An Integer parameter", 1080, 0) +gen.add("capturing_scan_multiplier", int_t, 1 << 5, "An Integer parameter", 1) +gen.add("acquisition_time", double_t, 1 << 6, "A double parameter", 1.0, 0.0) -size_enum = gen.enum([ gen.const("Small", int_t, 0, "A small constant"), - gen.const("Medium", int_t, 1, "A medium constant"), - gen.const("Large", int_t, 2, "A large constant"), - gen.const("ExtraLarge", int_t, 3, "An extra large constant")], - "An enum to set size") +trigger_enum = gen.enum([gen.const("Freerun", int_t, 0, "A small constant"), + gen.const("Software", int_t, 1, "A medium constant"), + gen.const("hardware", int_t, 2, "A large constant"), + gen.const("NoValue", int_t, 3, "An extra large constant")], + "An enum to set size") -gen.add("size", int_t, 0, "A size parameter which is edited via an enum", 1, 0, 3, edit_method=size_enum) +gen.add("trigger_mode", int_t, 1 << 7, "A size parameter which is edited via an enum", 1, 0, 3, edit_method=trigger_enum) -exit(gen.generate(PACKAGE, "phoxi_camera", "Tutorials")) +timeout_enum = gen.enum([gen.const("ZeroTimeout", int_t, 0, "A small constant"), + gen.const("Infinity", int_t, -1, "A medium constant"), + gen.const("LastStored", int_t, -2, "A large constant"), + gen.const("Default", int_t, -3, "An extra large constant")], + "An enum to set size") + +gen.add("timeout", int_t, 1 << 8, "A size parameter which is edited via an enum", -1, -3, 0, edit_method=timeout_enum) + +gen.add("processing_settings", double_t, 1 << 9, "A double parameter", 1.0, 0.0) + +gen.add("send_point_cloud", bool_t, 1 << 10, "A Boolean parameter", True) +gen.add("send_depth_map", bool_t, 1 << 11, "A Boolean parameter", True) +gen.add("send_confidence_map", bool_t, 1 << 12, "A Boolean parameter", True) +gen.add("send_texture", bool_t, 1 << 13, "A Boolean parameter", True) + +exit(gen.generate(PACKAGE, "phoxi_camera_node", "Tutorials")) diff --git a/msg/PhoXiSize.msg b/msg/PhoXiSize.msg new file mode 100644 index 0000000..97ff0d0 --- /dev/null +++ b/msg/PhoXiSize.msg @@ -0,0 +1,2 @@ +int32 Width +int32 Height \ No newline at end of file diff --git a/package.xml b/package.xml index 5f3af91..ebbb961 100644 --- a/package.xml +++ b/package.xml @@ -32,11 +32,11 @@ - + message_generation - + message_runtime catkin @@ -47,6 +47,7 @@ rospy sensor_msgs std_msgs + std_srvs tf dynamic_reconfigure pcl_ros @@ -55,6 +56,7 @@ rospy sensor_msgs std_msgs + std_srvs tf diff --git a/src/phoxi_camera_example.py b/src/phoxi_camera_example.py new file mode 100755 index 0000000..a7a96c0 --- /dev/null +++ b/src/phoxi_camera_example.py @@ -0,0 +1,27 @@ +#!/usr/bin/env python +import rospy +from phoxi_camera.srv import * +from std_srvs.srv import * + +if __name__ == "__main__": + rospy.init_node('phoxi_camera_example', anonymous=True) + while not rospy.is_shutdown(): + rospy.wait_for_service('phoxi_camera/get_device_list') + try: + get_device_list = rospy.ServiceProxy('phoxi_camera/get_device_list', GetDeviceList) + resp1 = get_device_list() + print "devices", resp1.out + name = "noConnectedCamera-03" + res_connect = rospy.ServiceProxy('phoxi_camera/connect_camera', ConnectCamera)(name) + print "connect to", name, res_connect + if res_connect.success: + res_star_acq = rospy.ServiceProxy('phoxi_camera/start_acquisition', Empty)() + res_trig = rospy.ServiceProxy('phoxi_camera/trigger_image', TriggerImage)() + res_get_fram = rospy.ServiceProxy('phoxi_camera/get_frame', GetFrame)(-1) + print "get_frame", res_get_fram + else: + print "cant connect" + except rospy.ServiceException, e: + print "Service call failed: %s" % e + res_dis = rospy.ServiceProxy('phoxi_camera/disconnect_camera', Empty)() + print "disconnect" diff --git a/src/phoxi_camera_node.cpp b/src/phoxi_camera_node.cpp index 1be0560..2ed9f66 100644 --- a/src/phoxi_camera_node.cpp +++ b/src/phoxi_camera_node.cpp @@ -1,27 +1,32 @@ #include #include -#include +#include #include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include //#define PHOXI_PCL_SUPPORT -void callback(pho_driver::TutorialsConfig &config, uint32_t level) { - ROS_INFO("Reconfigure Request: %d %f %s %s %d", - config.int_param, config.double_param, - config.str_param.c_str(), - config.bool_param ? "True" : "False", - config.size); -} - #include "PhoXi.h" #include +#include +#include + #if defined(_WIN32) #include #elif defined (__linux__) #include #endif -#include + #if defined(_WIN32) #define LOCAL_CROSS_SLEEP(Millis) Sleep(Millis) @@ -40,84 +45,233 @@ void callback(pho_driver::TutorialsConfig &config, uint32_t level) { #include //#include "Console/PhotoneoConsole.h" -int main(int argc, char **argv) { - ROS_INFO("Starting pho_driver ros..."); - ros::init(argc, argv, "pho_driver"); +pho::api::PPhoXi EvaluationScanner; +pho::api::PhoXiFactory Factory; +ros::Publisher pub; - ros::NodeHandle nh; - ros::Publisher pub; +void init_config(pho::api::PPhoXi &Scanner) { + std::cout << "cinit" << std::endl; + ros::param::set("~size_height", Scanner->Resolution->Height); + ros::param::set("~size_width", Scanner->Resolution->Width); + ros::param::set("~capturing_size_height", Scanner->CapturingMode->Resolution.Height); + ros::param::set("~capturing_size_width", Scanner->CapturingMode->Resolution.Width); + ros::param::set("~capturing_scan_multiplier", Scanner->CapturingSettings->ScanMultiplier); + ros::param::set("~acquisition_time", Scanner->AcquisitionTime); + ros::param::set("~trigger_mode", (pho::api::PhoXiTriggerMode::Value)(pho::api::PhoXiTriggerMode)Scanner->TriggerMode); + ros::param::set("~timeout", (int)(pho::api::PhoXiTimeout)Scanner->Timeout); + ros::param::set("~processing_settings", Scanner->ProcessingSettings->RequiredConfidence); + ros::param::set("~send_point_cloud", Scanner->OutputSettings->SendPointCloud); + ros::param::set("~send_depth_map", Scanner->OutputSettings->SendDepthMap); + ros::param::set("~send_confidence_map", Scanner->OutputSettings->SendConfidenceMap); + ros::param::set("~send_texture", Scanner->OutputSettings->SendTexture); +} - dynamic_reconfigure::Server server; - dynamic_reconfigure::Server::CallbackType f; +void callback(pho::api::PPhoXi &Scanner, phoxi_camera::TutorialsConfig &config, uint32_t level) { + if (EvaluationScanner == 0){ + return; + } + if (level & (1 << 1)) { + Scanner->Resolution->Height = config.size_height; + } + if (level & (1 << 2)) { + Scanner->Resolution->Width = config.size_width; + } + if (level & (1 << 3)) { + Scanner->CapturingMode->Resolution.Height = config.capturing_size_width; + } + if (level & (1 << 4)) { + Scanner->CapturingMode->Resolution.Width = config.capturing_size_width; + } + if (level & (1 << 5)) { + Scanner->CapturingSettings->ScanMultiplier = config.capturing_scan_multiplier; + } + if (level & (1 << 6)) { + Scanner->AcquisitionTime = config.acquisition_time; + } + if (level & (1 << 7)) { + Scanner->TriggerMode = config.trigger_mode; + } + if (level & (1 << 8)) { + Scanner->Timeout = config.timeout; + } + if (level & (1 << 9)) { + Scanner->ProcessingSettings->RequiredConfidence = config.processing_settings; + } + if (level & (1 << 10)) { + Scanner->OutputSettings->SendPointCloud = config.send_point_cloud; + } + if (level & (1 << 11)) { + Scanner->OutputSettings->SendDepthMap = config.send_depth_map; + } + if (level & (1 << 12)) { + Scanner->OutputSettings->SendConfidenceMap = config.send_confidence_map; + } + if (level & (1 << 13)) { + Scanner->OutputSettings->SendTexture = config.send_texture; + } +} - f = boost::bind(&callback, _1, _2); - server.setCallback(f); +std::vector get_device_list(){ + Factory.StartConsoleOutput("Admin-On"); + return Factory.GetDeviceList(); +} +bool get_device_list_service(phoxi_camera::GetDeviceList::Request &req, + phoxi_camera::GetDeviceList::Response &res) { + std::vector DeviceList = get_device_list(); + res.len = DeviceList.size(); + for (int i = 0; i < DeviceList.size(); ++i) { + res.out.push_back(DeviceList[i].HWIdentification); + } + return true; +} -LOCAL_CROSS_SLEEP(5000); - pub = nh.advertise> ("output", 1); - int k = 0; - while(ros::ok()){ - ROS_INFO("Spin loop"); - LOCAL_CROSS_SLEEP(1000); - pho::api::PhoXiFactory Factory; - Factory.StartConsoleOutput("Admin-On"); - std::vector DeviceList = Factory.GetDeviceList(); - for(int k = 0;k < DeviceList.size();k++){ - if(DeviceList[k].HWIdentification != "file") continue; - ROS_INFO("found at least one"); - pho::api::PPhoXi EvaluationScanner = Factory.Create(DeviceList[k]); - EvaluationScanner->Connect(); - if (EvaluationScanner->isAcquiring()) { - EvaluationScanner->StopAcquisition(); - } - - if (EvaluationScanner->isConnected()) { - EvaluationScanner->TriggerMode = pho::api::PhoXiTriggerMode::Software; - while (EvaluationScanner->GetFrame(0)) { - std::cout << "Cleaning Buffer" << std::endl; - } - EvaluationScanner->StartAcquisition(); - if (EvaluationScanner->isAcquiring()) { - for (int i = 0; i < 1; i++) { - if (EvaluationScanner->TriggerImage()) { - pho::api::PFrame MyFrame = EvaluationScanner->GetFrame(pho::api::PhoXiTimeout::Infinity); - EvaluationScanner->AcquisitionTime = 1.0; - if (MyFrame) { - std::cout << i << std::endl; - if (!MyFrame->PointCloud.Empty()) std::cout << "PointCloud: " << MyFrame->PointCloud.Size.Width << " x " << MyFrame->PointCloud.Size.Height << " Type: " << MyFrame->PointCloud.GetElementName() << std::endl; - if (!MyFrame->DepthMap.Empty()) std::cout << "DepthMap: " << MyFrame->DepthMap.Size.Width << " x " << MyFrame->DepthMap.Size.Height << " Type: " << MyFrame->DepthMap.GetElementName() << std::endl; - if (!MyFrame->Texture.Empty()) std::cout << "Texture: " << MyFrame->Texture.Size.Width << " x " << MyFrame->Texture.Size.Height << " Type: " << MyFrame->Texture.GetElementName() << std::endl; - if (!MyFrame->ConfidenceMap.Empty()) std::cout << "ConfidenceMap: " << MyFrame->ConfidenceMap.Size.Width << " x " << MyFrame->ConfidenceMap.Size.Height << " Type: " << MyFrame->ConfidenceMap.GetElementName() << std::endl; - //MyFrame->SaveAsPly("Test Software" + std::to_string(k) + " , " + std::to_string(i) + ".ply"); - //pcl::PointCloud MyPCLCloud; - //MyFrame->ConvertTo(MyPCLCloud); - //pcl::PCLPointCloud2 MyPCLCloud2; - //MyFrame->ConvertTo(MyPCLCloud2); - //pcl::PLYWriter Writer; - //Writer.writeBinary("Test Software PCL" + std::to_string(k) + " , " + std::to_string(i) + ".ply", MyPCLCloud2); - pcl::PointCloud cloud; - int h = MyFrame->PointCloud.Size.Height; - int w = MyFrame->PointCloud.Size.Width; - for (int i = 0; i < h; ++i) { - for (int j = 0; j < w; ++j) { - auto& point = MyFrame->PointCloud.At(i, j); - if (point.z > 10 && point.z < 10000) - cloud.push_back (pcl::PointXYZ (point.x, point.y, point.z)); - // cloud.push_back (pcl::PointXYZ (i, j, i+j)); - } - } - ROS_INFO("publishing"); - sensor_msgs::PointCloud2 output; - pcl::toROSMsg(cloud, output); - output.header.frame_id = "map"; - pub.publish (output); - } - } - } - } - } +bool connect_camera(phoxi_camera::ConnectCamera::Request &req, + phoxi_camera::ConnectCamera::Response &res) { + std::vector DeviceList = get_device_list(); + std::cout << "device list" << std::endl; + for (int i = 0; i < DeviceList.size(); i++) { + if(DeviceList[i].HWIdentification == req.name){ + EvaluationScanner = Factory.Create(DeviceList[i]); + EvaluationScanner->Connect(); + if (EvaluationScanner->isConnected()) { + init_config(EvaluationScanner); + res.success = true; + return true; } } + } + res.success = false; + return true; +} + +bool is_connected(phoxi_camera::IsConnected::Request &req, + phoxi_camera::IsConnected::Response &res) { + res.connected = EvaluationScanner->isConnected(); + return true; +} + +bool disconnect_camera(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) { + EvaluationScanner->Disconnect(); + return true; +} + + + +bool is_acquiring(phoxi_camera::IsAcquiring::Request &req, phoxi_camera::IsAcquiring::Response &res) { + res.is_acquiring = EvaluationScanner->isAcquiring(); + return true; +} + +bool start_acquisition(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) { + EvaluationScanner->StartAcquisition(); + return true; +} + +bool stop_acquisition(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) { + EvaluationScanner->StopAcquisition(); + return true; +} + +bool trigger_image(phoxi_camera::TriggerImage::Request &req, phoxi_camera::TriggerImage::Response &res){ + res.success = EvaluationScanner->TriggerImage(); + return true; +} + +void publish_frame(pho::api::PFrame MyFrame){ + if (MyFrame) { + if (!MyFrame->PointCloud.Empty()) + std::cout << "PointCloud: " << MyFrame->PointCloud.Size.Width << " x " << + MyFrame->PointCloud.Size.Height << " Type: " << + MyFrame->PointCloud.GetElementName() << std::endl; + if (!MyFrame->DepthMap.Empty()) + std::cout << "DepthMap: " << MyFrame->DepthMap.Size.Width << " x " << + MyFrame->DepthMap.Size.Height << " Type: " << MyFrame->DepthMap.GetElementName() << + std::endl; + if (!MyFrame->Texture.Empty()) + std::cout << "Texture: " << MyFrame->Texture.Size.Width << " x " << + MyFrame->Texture.Size.Height << " Type: " << MyFrame->Texture.GetElementName() << + std::endl; + if (!MyFrame->ConfidenceMap.Empty()) + std::cout << "ConfidenceMap: " << MyFrame->ConfidenceMap.Size.Width << " x " << + MyFrame->ConfidenceMap.Size.Height << " Type: " << + MyFrame->ConfidenceMap.GetElementName() << std::endl; + //MyFrame->SaveAsPly("Test Software" + std::to_string(k) + " , " + std::to_string(i) + ".ply"); + //pcl::PointCloud MyPCLCloud; + //MyFrame->ConvertTo(MyPCLCloud); + //pcl::PCLPointCloud2 MyPCLCloud2; + //MyFrame->ConvertTo(MyPCLCloud2); + //pcl::PLYWriter Writer; + //Writer.writeBinary("Test Software PCL" + std::to_string(k) + " , " + std::to_string(i) + ".ply", MyPCLCloud2); + pcl::PointCloud cloud; + int h = MyFrame->PointCloud.Size.Height; + int w = MyFrame->PointCloud.Size.Width; + for (int i = 0; i < h; ++i) { + for (int j = 0; j < w; ++j) { + auto &point = MyFrame->PointCloud.At(i, j); + if (point.z > 10 && point.z < 10000) + cloud.push_back(pcl::PointXYZ(point.x, point.y, point.z)); + // cloud.push_back (pcl::PointXYZ (i, j, i+j)); + } + } + ROS_INFO("publishing"); + sensor_msgs::PointCloud2 output; + pcl::toROSMsg(cloud, output); + output.header.frame_id = "map"; + pub.publish(output); + } +} + +bool get_frame(phoxi_camera::GetFrame::Request &req, phoxi_camera::GetFrame::Response &res){ + pho::api::PFrame MyFrame = EvaluationScanner->GetFrame(req.in); + if(MyFrame){ + publish_frame(MyFrame); + res.success = true; + } + else res.success = false; + return true; +} + +bool get_supported_capturing_modes(phoxi_camera::GetSupportedCapturingModes::Request &req, phoxi_camera::GetSupportedCapturingModes::Response &res){ + std::vector vec = EvaluationScanner->SupportedCapturingModes; + for(int i = 0;i< vec.size();i++){ + phoxi_camera::PhoXiSize a; + a.Width = vec[i].Resolution.Width; + a.Height = vec[i].Resolution.Height; + res.supported_capturing_modes.push_back(a); + } + return true; +} + +bool get_hardware_identification(phoxi_camera::GetHardwareIdentification::Request &req, phoxi_camera::GetHardwareIdentification::Response &res){ + res.hardware_identification = EvaluationScanner->HardwareIdentification; + return true; +} + +int main(int argc, char **argv) { + ROS_INFO("Starting phoxi_camera ros..."); + ros::init(argc, argv, "phoxi_camera"); + ros::NodeHandle nh("~"); + + dynamic_reconfigure::Server server; + dynamic_reconfigure::Server::CallbackType f; + + f = boost::bind(&callback, boost::ref(EvaluationScanner), _1, _2); + server.setCallback(f); + + ros::ServiceServer service_get_device_list = nh.advertiseService("get_device_list", get_device_list_service); + ros::ServiceServer service_connect_camera = nh.advertiseService("connect_camera", connect_camera); + ros::ServiceServer service_is_connected = nh.advertiseService("is_connected", is_connected); + ros::ServiceServer service_is_acquiring = nh.advertiseService("is_acquiring", is_acquiring); + ros::ServiceServer service_start_acquisition = nh.advertiseService("start_acquisition", start_acquisition); + ros::ServiceServer service_stop_acquisition = nh.advertiseService("stop_acquisition", stop_acquisition); + ros::ServiceServer service_trigger_image = nh.advertiseService("trigger_image", trigger_image); + ros::ServiceServer service_get_frame = nh.advertiseService("get_frame", get_frame); + ros::ServiceServer service_disconnect_camera = nh.advertiseService("disconnect_camera", disconnect_camera); + ros::ServiceServer service_get_hardware_identification = nh.advertiseService("get_hardware_indentification", get_hardware_identification); + ros::ServiceServer service_get_supported_capturing_modes = nh.advertiseService("get_supported_capturing_modes", get_supported_capturing_modes); + pub = nh.advertise < pcl::PointCloud < pcl::PointXYZ >> ("output", 1); + ROS_INFO("Ready"); + ros::spin(); return 0; } diff --git a/srv/ConnectCamera.srv b/srv/ConnectCamera.srv new file mode 100644 index 0000000..dc5ebb7 --- /dev/null +++ b/srv/ConnectCamera.srv @@ -0,0 +1,3 @@ +string name +--- +bool success \ No newline at end of file diff --git a/srv/GetDeviceList.srv b/srv/GetDeviceList.srv new file mode 100644 index 0000000..7473db3 --- /dev/null +++ b/srv/GetDeviceList.srv @@ -0,0 +1,3 @@ +--- +int64 len +string[] out diff --git a/srv/GetFrame.srv b/srv/GetFrame.srv new file mode 100644 index 0000000..1a9662a --- /dev/null +++ b/srv/GetFrame.srv @@ -0,0 +1,3 @@ +int64 in +--- +bool success \ No newline at end of file diff --git a/srv/GetHardwareIdentification.srv b/srv/GetHardwareIdentification.srv new file mode 100644 index 0000000..84ef4c7 --- /dev/null +++ b/srv/GetHardwareIdentification.srv @@ -0,0 +1,2 @@ +--- +string hardware_identification \ No newline at end of file diff --git a/srv/GetSupportedCapturingModes.srv b/srv/GetSupportedCapturingModes.srv new file mode 100644 index 0000000..daaeb9a --- /dev/null +++ b/srv/GetSupportedCapturingModes.srv @@ -0,0 +1,2 @@ +--- +PhoXiSize[] supported_capturing_modes \ No newline at end of file diff --git a/srv/IsAcquiring.srv b/srv/IsAcquiring.srv new file mode 100644 index 0000000..3d699f5 --- /dev/null +++ b/srv/IsAcquiring.srv @@ -0,0 +1,2 @@ +--- +bool is_acquiring \ No newline at end of file diff --git a/srv/IsConnected.srv b/srv/IsConnected.srv new file mode 100644 index 0000000..e50fe50 --- /dev/null +++ b/srv/IsConnected.srv @@ -0,0 +1,2 @@ +--- +bool connected \ No newline at end of file diff --git a/srv/TriggerImage.srv b/srv/TriggerImage.srv new file mode 100644 index 0000000..1308cc2 --- /dev/null +++ b/srv/TriggerImage.srv @@ -0,0 +1,2 @@ +--- +bool success \ No newline at end of file