ik_ros_i.h
Go to the documentation of this file.
1 #ifndef PHIDGETS_IK_IK_ROS_I_H
2 #define PHIDGETS_IK_IK_ROS_I_H
3 
4 #include <phidgets_api/ik.h>
5 #include <ros/ros.h>
6 #include <std_msgs/Bool.h>
7 #include <std_msgs/Float32.h>
8 #include "phidgets_msgs/SetDigitalOutput.h"
9 
10 #include <memory>
11 #include <vector>
12 
13 namespace phidgets {
14 
16 {
17  public:
18  explicit OutputSetter(IK* ik, int index);
19  void set_msg_callback(const std_msgs::Bool::ConstPtr& msg);
21 
22  protected:
23  IK* ik_;
24  int index_;
25 };
26 
27 class IKRosI final : public IK
28 {
29  public:
30  explicit IKRosI(ros::NodeHandle nh, ros::NodeHandle nh_private);
31 
32  private:
33  int n_in;
34  int n_out;
35  int n_sensors;
36  std::vector<ros::Publisher> in_pubs_;
37  std::vector<ros::Publisher> sensor_pubs_;
39  std::vector<std::shared_ptr<OutputSetter> > out_subs_;
40 
43 
44  const float VREF;
45 
46  void initDevice();
47  void sensorHandler(int index, int sensorValue) override;
48  void inputHandler(int index, int inputValue) override;
49 
50  bool set_srv_callback(phidgets_msgs::SetDigitalOutput::Request& req,
51  phidgets_msgs::SetDigitalOutput::Response& res);
52 };
53 
54 } // namespace phidgets
55 
56 #endif // PHIDGETS_IK_IK_ROS_I_H
std::vector< ros::Publisher > sensor_pubs_
Definition: ik_ros_i.h:37
ros::NodeHandle nh_
Definition: ik_ros_i.h:41
const float VREF
Definition: ik_ros_i.h:44
std::vector< ros::Publisher > in_pubs_
Definition: ik_ros_i.h:36
OutputSetter(IK *ik, int index)
Definition: ik_ros_i.cpp:106
std::vector< std::shared_ptr< OutputSetter > > out_subs_
Definition: ik_ros_i.h:39
void set_msg_callback(const std_msgs::Bool::ConstPtr &msg)
Definition: ik_ros_i.cpp:100
ros::ServiceServer out_srv_
Definition: ik_ros_i.h:38
ros::NodeHandle nh_private_
Definition: ik_ros_i.h:42
ros::Subscriber subscription
Definition: ik_ros_i.h:20


phidgets_ik
Author(s): James Sarrett, Russel Howe
autogenerated on Fri Apr 9 2021 02:56:07