43 namespace joint_relay_handler
46 bool JointRelayHandler::init(
SmplMsgConnection* connection, std::vector<std::string>& joint_names)
48 this->pub_joint_control_state_ =
49 this->node_.advertise<control_msgs::FollowJointTrajectoryFeedback>(
"feedback_states", 1);
51 this->pub_joint_sensor_state_ = this->node_.advertise<sensor_msgs::JointState>(
"joint_states",1);
54 this->all_joint_names_ = joint_names;
63 if (!joint_msg.
init(in))
65 LOG_ERROR(
"Failed to initialize joint message");
69 return internalCB(joint_msg);
74 control_msgs::FollowJointTrajectoryFeedback control_state;
75 sensor_msgs::JointState sensor_state;
78 if (create_messages(in, &control_state, &sensor_state))
80 this->pub_joint_control_state_.publish(control_state);
81 this->pub_joint_sensor_state_.publish(sensor_state);
91 this->getConnection()->sendMsg(reply);
99 control_msgs::FollowJointTrajectoryFeedback* control_state,
100 sensor_msgs::JointState* sensor_state)
103 std::vector<double> all_joint_pos(all_joint_names_.size());
104 for (
int i=0; i<all_joint_names_.size(); ++i)
108 all_joint_pos[i] = value;
110 LOG_ERROR(
"Failed to parse #%d value from JointMessage", i);
114 std::vector<double> xform_joint_pos;
115 if (!transform(all_joint_pos, &xform_joint_pos))
117 LOG_ERROR(
"Failed to transform joint positions");
122 std::vector<double> pub_joint_pos;
123 std::vector<std::string> pub_joint_names;
124 if (!select(xform_joint_pos, all_joint_names_, &pub_joint_pos, &pub_joint_names))
126 LOG_ERROR(
"Failed to select joints for publishing");
131 control_msgs::FollowJointTrajectoryFeedback tmp_control_state;
133 tmp_control_state.joint_names = pub_joint_names;
134 tmp_control_state.actual.positions = pub_joint_pos;
135 *control_state = tmp_control_state;
137 sensor_msgs::JointState tmp_sensor_state;
139 tmp_sensor_state.name = pub_joint_names;
140 tmp_sensor_state.position = pub_joint_pos;
141 *sensor_state = tmp_sensor_state;
146 bool JointRelayHandler::select(
const std::vector<double>& all_joint_pos,
const std::vector<std::string>& all_joint_names,
147 std::vector<double>* pub_joint_pos, std::vector<std::string>* pub_joint_names)
149 ROS_ASSERT(all_joint_pos.size() == all_joint_names.size());
151 pub_joint_pos->clear();
152 pub_joint_names->clear();
155 for (
int i=0; i<all_joint_pos.size(); ++i)
157 if (all_joint_names[i].empty())
160 pub_joint_pos->push_back(all_joint_pos[i]);
161 pub_joint_names->push_back(all_joint_names[i]);