DummyHal.cpp
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 
19 
21 
22  std::string out;
23 
24  _hal_joint_state_pub = nh->advertise<sensor_msgs::JointState>("/dummyHal/joint_command", 1);
25  _hal_joint_state_sub = nh->subscribe("/dummyHal/joint_states", 1, &ROSEE::DummyHal::hal_js_clbk, this);
26 }
27 
28 
30  //do nothing, it is the hal_js_clbk who "sense"
31  return true;
32 }
33 
35  _hal_joint_state_pub.publish(_mr_msg);
36  return true;
37 }
38 
39 void ROSEE::DummyHal::hal_js_clbk(const sensor_msgs::JointState::ConstPtr& msg) {
40 
41  _js_msg = *msg;
42 }
43 
ROSEE::DummyHal::_hal_joint_state_sub
ros::Subscriber _hal_joint_state_sub
this will subscribe to joint_state_publisher
Definition: DummyHal.h:56
ROSEE::DummyHal::DummyHal
DummyHal(ros::NodeHandle *nh)
Definition: DummyHal.cpp:20
ROSEE::EEHal
Class representing an end-effector.
Definition: EEHal.h:54
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ROSEE::DummyHal::move
virtual bool move() override
Definition: DummyHal.cpp:34
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ROSEE::DummyHal::sense
virtual bool sense() override
Definition: DummyHal.cpp:29
DummyHal.h
ROSEE::DummyHal::hal_js_clbk
void hal_js_clbk(const sensor_msgs::JointState::ConstPtr &msg)
Definition: DummyHal.cpp:39
ROSEE::DummyHal::_hal_joint_state_pub
ros::Publisher _hal_joint_state_pub
this will publish to joint_state_publisher
Definition: DummyHal.h:51
ros::NodeHandle


end-effector
Author(s): Luca Muratore , Davide Torielli , Liana Bertoni
autogenerated on Sat Dec 14 2024 03:49:26