Skip to content

Commit

Permalink
fixed publish of pantilt position
Browse files Browse the repository at this point in the history
  • Loading branch information
atiderko authored and Robot User committed May 4, 2018
1 parent dfa39b4 commit 730f3ca
Showing 1 changed file with 12 additions and 13 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -110,20 +110,19 @@ void PanTiltJointPositionSensorClient_ReceiveFSM::handleReportPanTiltJointPositi
pos_tilt32.data = joint2_position;
p_pub_pos_tilt32.publish(pos_tilt32);
if (p_use_posestamped) {
geometry_msgs::PoseStamped cmd_pos;
geometry_msgs::PoseStamped cmd_pose;
tf::Quaternion quat = tf::createQuaternionFromRPY(0.0, joint2_position, joint1_position);
geometry_msgs::PoseStamped pose;
pose.header.frame_id = p_tf_frame_pantilt;
pose.header.stamp = ros::Time::now();
pose.pose.position.x = 0;
pose.pose.position.y = 0;
pose.pose.position.z = 0;
pose.pose.orientation.x = quat.x();
pose.pose.orientation.y = quat.y();
pose.pose.orientation.z = quat.z();
pose.pose.orientation.w = quat.w();

p_sub_pos_stamped.publish(cmd_pos);
cmd_pose.header.frame_id = p_tf_frame_pantilt;
cmd_pose.header.stamp = ros::Time::now();
cmd_pose.pose.position.x = 0;
cmd_pose.pose.position.y = 0;
cmd_pose.pose.position.z = 0;
cmd_pose.pose.orientation.x = quat.x();
cmd_pose.pose.orientation.y = quat.y();
cmd_pose.pose.orientation.z = quat.z();
cmd_pose.pose.orientation.w = quat.w();

p_sub_pos_stamped.publish(cmd_pose);
}
}

Expand Down

0 comments on commit 730f3ca

Please sign in to comment.