gripper_joint_state_publisher.cpp
Go to the documentation of this file.
1 // Copyright (c) 2017 Franka Emika GmbH
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
3 #include <franka/exception.h>
4 #include <franka/gripper.h>
5 #include <ros/ros.h>
6 #include <sensor_msgs/JointState.h>
7 
8 int main(int argc, char** argv) {
9  ros::init(argc, argv, "gripper_joint_state_publisher");
10  ros::NodeHandle node_handle("~");
11 
12  std::vector<std::string> joint_names;
13  node_handle.getParam("joint_names", joint_names);
14 
15  std::string robot_ip;
16  node_handle.getParam("robot_ip", robot_ip);
17 
18  double publish_rate;
19  node_handle.getParam("publish_rate", publish_rate);
20 
21  ros::Rate rate(publish_rate);
22 
23  sensor_msgs::JointState states;
24  states.effort.resize(joint_names.size());
25  states.name.resize(joint_names.size());
26  states.position.resize(joint_names.size());
27  states.velocity.resize(joint_names.size());
28 
29  for (size_t i = 0; i < joint_names.size(); i++) {
30  states.name[i] = joint_names[i];
31  }
32 
33  ros::Publisher publisher = node_handle.advertise<sensor_msgs::JointState>("joint_states", 1);
34 
35  try {
36  franka::Gripper gripper(robot_ip);
37 
38  while (ros::ok()) {
39  franka::GripperState gripper_state = gripper.readOnce();
40  states.header.stamp = ros::Time::now();
41  for (size_t i = 0; i < joint_names.size(); i++) {
42  states.position[i] = gripper_state.width * 0.5;
43  states.velocity[i] = 0.0;
44  states.effort[i] = 0.0;
45  }
46  publisher.publish(states);
47  ros::spinOnce();
48  rate.sleep();
49  }
50 
51  } catch (const franka::Exception& e) {
52  ROS_ERROR_STREAM("Exception: " << e.what());
53  return -1;
54  }
55 
56  return 0;
57 }
void publish(const boost::shared_ptr< M > &message) const
GripperState readOnce() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL bool ok()
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool sleep()
bool getParam(const std::string &key, std::string &s) const
static Time now()
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void spinOnce()


franka_visualization
Author(s): Franka Emika GmbH
autogenerated on Fri Oct 23 2020 03:47:22