cob_phidgets_sim_node.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #include <ros/ros.h>
19 #include <cob_phidgets/SetDataRate.h>
20 #include <cob_phidgets/SetDigitalSensor.h>
21 #include <cob_phidgets/SetTriggerValue.h>
22 
23 #include <cob_phidgets/AnalogSensor.h>
24 #include <cob_phidgets/DigitalSensor.h>
25 
27 {
28 public:
30  {
31  _pubAnalog = _nh.advertise<cob_phidgets::AnalogSensor>("analog_sensors", 1);
32  _pubDigital = _nh.advertise<cob_phidgets::DigitalSensor>("digital_sensors", 1);
33  _subDigital = _nh.subscribe("set_digital_sensor", 1, &PhidgetIKROSSim::onDigitalOutCallback, this);
34 
38  };
40 private:
48 
49  auto onDigitalOutCallback(const cob_phidgets::DigitalSensorConstPtr& msg) -> void
50  {
51 
52  }
53  auto setDigitalOutCallback(cob_phidgets::SetDigitalSensor::Request &req,
54  cob_phidgets::SetDigitalSensor::Response &res) -> bool
55  {
56  res.state = req.state;
57  res.uri = req.uri;
58  return true;
59  }
60  auto setDataRateCallback(cob_phidgets::SetDataRate::Request &req,
61  cob_phidgets::SetDataRate::Response &res) -> bool
62  {
63  return true;
64  }
65  auto setTriggerValueCallback(cob_phidgets::SetTriggerValue::Request &req,
66  cob_phidgets::SetTriggerValue::Response &res) -> bool
67  {
68  return true;
69  }
70 };
71 
72 
73 int main(int argc, char **argv)
74 {
75  ros::init(argc, argv, "cob_phidgets_sim");
76  PhidgetIKROSSim cob_phidgets_sim;
77  ros::spin();
78  return 0;
79 }
auto setDataRateCallback(cob_phidgets::SetDataRate::Request &req, cob_phidgets::SetDataRate::Response &res) -> bool
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber _subDigital
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
auto setTriggerValueCallback(cob_phidgets::SetTriggerValue::Request &req, cob_phidgets::SetTriggerValue::Response &res) -> bool
ros::ServiceServer _srvTriggerValue
ros::ServiceServer _srvDataRate
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros::Publisher _pubAnalog
ros::Publisher _pubDigital
auto setDigitalOutCallback(cob_phidgets::SetDigitalSensor::Request &req, cob_phidgets::SetDigitalSensor::Response &res) -> bool
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void spin()
ros::ServiceServer _srvDigitalOut
auto onDigitalOutCallback(const cob_phidgets::DigitalSensorConstPtr &msg) -> void
int main(int argc, char **argv)


cob_phidgets
Author(s): Florian Weisshardt
autogenerated on Thu Nov 17 2022 03:17:33