ROSEndEffector
ROS End-Effector package: provides a ROS-based set of standard interfaces to command robotics end-effectors in an agnostic fashion.
DummyHal.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2019 IIT-HHCM
3  * Author: Luca Muratore
4  * email: luca.muratore@iit.it
5  *
6  * Licensed under the Apache License, Version 2.0 (the "License");
7  * you may not use this file except in compliance with the License.
8  * You may obtain a copy of the License at
9  * http://www.apache.org/licenses/LICENSE-2.0
10  *
11  * Unless required by applicable law or agreed to in writing, software
12  * distributed under the License is distributed on an "AS IS" BASIS,
13  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14  * See the License for the specific language governing permissions and
15  * limitations under the License.
16 */
17 
18 #ifndef __ROSEE_DUMMY_HAL__
19 #define __ROSEE_DUMMY_HAL__
20 
21 #include <ros/ros.h>
22 
23 #include <end_effector/HAL/EEHal.h>
24 
25 #include <string>
26 #include <memory>
27 
28 namespace ROSEE {
29 
34  class DummyHal : public EEHal {
35 
36  public:
37 
38  typedef std::shared_ptr<DummyHal> Ptr;
39  typedef std::shared_ptr<const DummyHal> ConstPtr;
40 
41  DummyHal( ros::NodeHandle* nh);
42  virtual ~DummyHal() {};
43 
44  virtual bool sense() override;
45  virtual bool move() override;
46 
47  private:
51  ros::Publisher _hal_joint_state_pub;
52 
56  ros::Subscriber _hal_joint_state_sub;
57 
58  void hal_js_clbk(const sensor_msgs::JointState::ConstPtr& msg);
59 
60  };
61 
63 }
64 
65 #endif // __ROSEE_DUMMY_HAL__
virtual bool move() override
Definition: DummyHal.cpp:34
ros::Subscriber _hal_joint_state_sub
this will subscribe to joint_state_publisher
Definition: DummyHal.h:56
Class representing an end-effector.
Definition: DummyHal.h:34
DummyHal(ros::NodeHandle *nh)
Definition: DummyHal.cpp:20
void hal_js_clbk(const sensor_msgs::JointState::ConstPtr &msg)
Definition: DummyHal.cpp:39
ros::Publisher _hal_joint_state_pub
this will publish to joint_state_publisher
Definition: DummyHal.h:51
virtual ~DummyHal()
Definition: DummyHal.h:42
std::shared_ptr< DummyHal > Ptr
Definition: DummyHal.h:38
Class representing an end-effector.
Definition: EEHal.h:54
virtual bool sense() override
Definition: DummyHal.cpp:29
#define HAL_CREATE_OBJECT(className)
Definition: EEHal.h:42
std::shared_ptr< const DummyHal > ConstPtr
Definition: DummyHal.h:39