18 #include <std_msgs/Float64.h> 26 std_msgs::Float64 grip_joint_msg, grip_joint_msg_2;
28 grip_joint_msg.data = msg->data;
29 grip_joint_msg_2.data = msg->data * (1.0 / 1.1);
31 g_rh_r2_joint_pub.
publish(grip_joint_msg_2);
32 g_rh_l1_joint_pub.
publish(grip_joint_msg);
33 g_rh_l2_joint_pub.
publish(grip_joint_msg_2);
36 int main(
int argc,
char **argv)
38 ros::init(argc, argv,
"gazebo_gripper_publisher");
41 g_rh_r2_joint_pub = nh.
advertise<std_msgs::Float64>(
"/rh_p12_rn/rh_r2_position/command", 0);
42 g_rh_l1_joint_pub = nh.
advertise<std_msgs::Float64>(
"/rh_p12_rn/rh_l1_position/command", 0);
43 g_rh_l2_joint_pub = nh.
advertise<std_msgs::Float64>(
"/rh_p12_rn/rh_l2_position/command", 0);
ros::Publisher g_rh_l1_joint_pub
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)
ros::Publisher g_rh_l2_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)
ros::Publisher g_rh_r2_joint_pub
void rhJointCallback(const std_msgs::Float64::ConstPtr &msg)