nao_footprint.hpp
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Aldebaran
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 */
17 
18 #ifndef NAO_FOOTPRINT_HPP
19 #define NAO_FOOTPRINT_HPP
20 
21 /*
22 * ROS includes
23 */
25 #include <geometry_msgs/Transform.h>
27 
28 /*
29 * loca includes
30 */
31 #include "../helpers/transform_helpers.hpp"
32 
33 namespace naoqi
34 {
35 namespace converter
36 {
37 namespace nao
38 {
39 
40 inline void addBaseFootprint( boost::shared_ptr<tf2_ros::Buffer> tf2_buffer, std::vector<geometry_msgs::TransformStamped>& tf_transforms, const ros::Time& time )
41 {
42  bool canTransform = tf2_buffer->canTransform("odom", "l_sole", time, ros::Duration(0.1) );
43  if (!canTransform)
44  {
45  ROS_ERROR_STREAM("Do not calculate NAO Footprint, no transform possible " << time);
46  return;
47  }
48 
49  geometry_msgs::TransformStamped tf_odom_to_base, tf_odom_to_left_foot, tf_odom_to_right_foot;
50  try {
51  // TRANSFORM THEM DIRECTLY INTO TRANSFORM
52  tf_odom_to_left_foot = tf2_buffer->lookupTransform("odom", "l_sole", time );
53  tf_odom_to_right_foot = tf2_buffer->lookupTransform("odom", "r_sole", time );
54  tf_odom_to_base = tf2_buffer->lookupTransform("odom", "base_link", time );
55  } catch (const tf2::TransformException& ex){
56  ROS_ERROR("NAO Footprint error %s",ex.what());
57  return ;
58  }
59  // middle of both feet
60  // z = fix to the lowest foot
61  tf2::Vector3 new_origin(
62  float(tf_odom_to_right_foot.transform.translation.x + tf_odom_to_left_foot.transform.translation.x)/2.0,
63  float(tf_odom_to_right_foot.transform.translation.y + tf_odom_to_left_foot.transform.translation.y)/2.0,
64  std::min(tf_odom_to_left_foot.transform.translation.z, tf_odom_to_right_foot.transform.translation.z)
65  );
66 
67  // adjust yaw according to torso orientation, all other angles 0 (= in z-plane)
68  double yaw = helpers::transform::getYaw( tf_odom_to_base.transform ) ;
69  tf2::Quaternion new_q;
70  new_q.setRPY(0.0f, 0.0f, yaw);
71  tf2::Transform tf_odom_to_footprint( new_q, new_origin);
72 
73  // way too complicated here, there should be proper conversions!
74  tf2::Quaternion q( tf_odom_to_base.transform.rotation.x,
75  tf_odom_to_base.transform.rotation.y,
76  tf_odom_to_base.transform.rotation.z,
77  tf_odom_to_base.transform.rotation.w
78  );
79  tf2::Vector3 r( tf_odom_to_base.transform.translation.x,
80  tf_odom_to_base.transform.translation.y,
81  tf_odom_to_base.transform.translation.z
82  );
83  tf2::Transform tf_odom_to_base_conv( q,r);
84  //tf2::Transform tf_odom_to_base_conv;
85  //tf2::convert( tf_odom_to_base.transform, tf_odom_to_base_conv );
86  tf2::Transform tf_base_to_footprint = tf_odom_to_base_conv.inverse() * tf_odom_to_footprint;
87 
88  // convert it back to geometry_msgs
89  geometry_msgs::TransformStamped message;
90  //message.transform = tf2::toMsg(tf_base_to_footprint);
91  message.header.stamp = time;
92  message.header.frame_id = "base_link";
93  message.child_frame_id = "base_footprint";
94 
95  message.transform.rotation.x = tf_base_to_footprint.getRotation().x();
96  message.transform.rotation.y = tf_base_to_footprint.getRotation().y();
97  message.transform.rotation.z = tf_base_to_footprint.getRotation().z();
98  message.transform.rotation.w = tf_base_to_footprint.getRotation().w();
99  message.transform.translation.x = tf_base_to_footprint.getOrigin().x();
100  message.transform.translation.y = tf_base_to_footprint.getOrigin().y();
101  message.transform.translation.z = tf_base_to_footprint.getOrigin().z();
102 
103  //tf::transformTFToMsg( tf_base_to_footprint, message.transform);
104  // publish transform with parent m_baseFrameId and new child m_baseFootPrintID
105  // i.e. transform from m_baseFrameId to m_baseFootPrintID
106  tf2_buffer->setTransform( message, "naoqiconverter", false );
107  tf_transforms.push_back( message );
108 }
109 
110 } // nao
111 } // converter
112 } // naoqi
113 
114 #endif
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
f
Quaternion getRotation() const
void addBaseFootprint(boost::shared_ptr< tf2_ros::Buffer > tf2_buffer, std::vector< geometry_msgs::TransformStamped > &tf_transforms, const ros::Time &time)
double getYaw(const geometry_msgs::Pose &pose)
TF2SIMD_FORCE_INLINE Vector3 & getOrigin()
Transform inverse() const
#define ROS_ERROR_STREAM(args)
#define ROS_ERROR(...)


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 15 2020 03:24:26