tool_pose_tf_broadcaster.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 Copyright [2017] [Frantisek Durovsky]
3 
4 Licensed under the Apache License, Version 2.0 (the "License");
5 you may not use this file except in compliance with the License.
6 You may obtain a copy of the License at
7 
8  http://www.apache.org/licenses/LICENSE-2.0
9 
10 Unless required by applicable law or agreed to in writing, software
11 distributed under the License is distributed on an "AS IS" BASIS,
12 WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 See the License for the specific language governing permissions and
14 limitations under the License.
15  *********************************************************************/
16 
18 
20 {
21 
22 }
23 
25 {
26 
27 }
28 
29 void Broadcaster::poseCallback(const geometry_msgs::PoseConstPtr& msg){
30 
31  // Check data validity (Quaternion x^2 + y^2 + z^2 + w^2 = 1)
32  double quaternion_sum = pow(msg->orientation.x, 2)
33  + pow(msg->orientation.y, 2)
34  + pow(msg->orientation.z, 2)
35  + pow(msg->orientation.w, 2);
36 
37  if (abs(1 -quaternion_sum) < 0.01)
38  {
39  // Tool Pose transform
40  origin.setX(msg->position.x);
41  origin.setY(msg->position.y);
42  origin.setZ(msg->position.z);
43 
44  orientation.setX(msg->orientation.x);
45  orientation.setY(msg->orientation.y);
46  orientation.setZ(msg->orientation.z);
47  orientation.setW(msg->orientation.w);
48 
51 
52  br.sendTransform(tf::StampedTransform(transform, ros::Time::now(), "base_link", "real_robot_tool_pose"));
53  }
54 }
55 
56 
57 int main(int argc, char** argv){
58  ros::init(argc, argv, "tool_pose_tf_broadcaster");
59  ros::NodeHandle nh;
60 
61  Broadcaster broadcaster;
62 
63  ros::Subscriber sub = nh.subscribe("real_robot_tool_pose", 1, &Broadcaster::poseCallback, &broadcaster);
64 
65  ROS_INFO("Tool Pose TF Broadcater running!");
66  ros::spin();
67  return 0;
68 }
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
void poseCallback(const geometry_msgs::PoseConstPtr &msg)
TFSIMD_FORCE_INLINE void setX(tfScalar x)
TFSIMD_FORCE_INLINE void setY(tfScalar y)
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)
TFSIMD_FORCE_INLINE void setZ(tfScalar z)
tf::Transform transform
ROSCPP_DECL void spin(Spinner &spinner)
tf::TransformBroadcaster br
int main(int argc, char **argv)
#define ROS_INFO(...)
void sendTransform(const StampedTransform &transform)
static Time now()
tf::Quaternion orientation
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)


binpicking_simple_utils
Author(s): Frantisek Durovsky
autogenerated on Mon Jun 10 2019 12:47:25