25 #include <std_msgs/Float64.h> 32 std_msgs::Float64 grip_joint_msg;
34 grip_joint_msg.data = msg->data;
36 g_left_arm_grip_joint_pub.
publish(grip_joint_msg);
41 std_msgs::Float64 grip_joint_msg;
43 grip_joint_msg.data = msg->data;
45 g_right_arm_grip_joint_pub.
publish(grip_joint_msg);
48 int main(
int argc,
char **argv)
50 ros::init(argc, argv,
"gazebo_gripper_publisher");
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);
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