gazebo_grip_pub.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2018 ROBOTIS CO., LTD.
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  * gazebo_grip_pub.cpp
19  *
20  * Created on: Jul 11, 2015
21  * Author: SCH
22  */
23 
24 #include <ros/ros.h>
25 #include <std_msgs/Float64.h>
26 
29 
30 void leftArmGripJointCallback(const std_msgs::Float64::ConstPtr& msg)
31 {
32  std_msgs::Float64 grip_joint_msg;
33 
34  grip_joint_msg.data = msg->data;
35 
36  g_left_arm_grip_joint_pub.publish(grip_joint_msg);
37 }
38 
39 void rightArmGripJointCallback(const std_msgs::Float64::ConstPtr& msg)
40 {
41  std_msgs::Float64 grip_joint_msg;
42 
43  grip_joint_msg.data = msg->data;
44 
45  g_right_arm_grip_joint_pub.publish(grip_joint_msg);
46 }
47 
48 int main(int argc, char **argv)
49 {
50  ros::init(argc, argv, "gazebo_gripper_publisher");
51  ros::NodeHandle nh("~");
52 
53  g_left_arm_grip_joint_pub = nh.advertise<std_msgs::Float64>("/thormang3/l_arm_grip_1_position/command", 0);
54  g_right_arm_grip_joint_pub = nh.advertise<std_msgs::Float64>("/thormang3/r_arm_grip_1_position/command", 0);
55 
56  ros::Subscriber l_arm_grip_joint_sub = nh.subscribe("/thormang3/l_arm_grip_position/command", 5, leftArmGripJointCallback);
57  ros::Subscriber r_arm_grip_joint_sub = nh.subscribe("/thormang3/r_arm_grip_position/command", 5, rightArmGripJointCallback);
58 
59  ros::spin();
60 
61  return 0;
62 }
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void rightArmGripJointCallback(const std_msgs::Float64::ConstPtr &msg)
ros::Publisher g_left_arm_grip_joint_pub
ROSCPP_DECL void spin(Spinner &spinner)
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void leftArmGripJointCallback(const std_msgs::Float64::ConstPtr &msg)
ros::Publisher g_right_arm_grip_joint_pub


thormang3_gazebo
Author(s): SCH
autogenerated on Mon Jun 10 2019 15:35:04