omx_gripper_sub_publisher.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 /* Authors: Darby Lim, Hye-Jong KIM, Ryan Shim, Yong-Ho Na */
18 
19 #include <ros/ros.h>
20 #include <std_msgs/Float64.h>
21 
23 
24 void gripperJointCallback(const std_msgs::Float64::ConstPtr& msg)
25 {
27 }
28 
29 int main(int argc, char **argv)
30 {
31  ros::init(argc, argv, "gripper_sub_publisher");
32  ros::NodeHandle node_handle("");
33 
34  ros::Subscriber gripper_joint_sub = node_handle.subscribe("gripper_position/command", 10, gripperJointCallback);
35  gripper_joint_sub_pub = node_handle.advertise<std_msgs::Float64>("gripper_sub_position/command", 10);
36 
37  ros::spin();
38  return 0;
39 }
gripper_joint_sub_pub
ros::Publisher gripper_joint_sub_pub
Definition: omx_gripper_sub_publisher.cpp:22
ros::Publisher
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
gripperJointCallback
void gripperJointCallback(const std_msgs::Float64::ConstPtr &msg)
Definition: omx_gripper_sub_publisher.cpp:24
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
main
int main(int argc, char **argv)
Definition: omx_gripper_sub_publisher.cpp:29
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
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())
ros::spin
ROSCPP_DECL void spin()
ros::NodeHandle
ros::Subscriber


open_manipulator_gazebo
Author(s): Darby Lim , Hye-Jong KIM , Ryan Shim , Yong-Ho Na
autogenerated on Wed Mar 2 2022 00:42:40