Skip to content

Commit

Permalink
Missing tf2 include and tf2 exception type (#103)
Browse files Browse the repository at this point in the history
* Add missing include tf2_ros/buffer.h
* Catch tf2::TransformException
  • Loading branch information
sloretz authored and nlyubova committed Feb 14, 2018
1 parent 9fe18ba commit a83ec33
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 1 deletion.
1 change: 1 addition & 0 deletions src/converters/joint_state.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
*/
#include <urdf/model.h>
#include <sensor_msgs/JointState.h>
#include <tf2_ros/buffer.h>
#include <robot_state_publisher/robot_state_publisher.h>

namespace naoqi
Expand Down
2 changes: 1 addition & 1 deletion src/converters/nao_footprint.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ inline void addBaseFootprint( boost::shared_ptr<tf2_ros::Buffer> tf2_buffer, std
tf_odom_to_left_foot = tf2_buffer->lookupTransform("odom", "l_sole", time );
tf_odom_to_right_foot = tf2_buffer->lookupTransform("odom", "r_sole", time );
tf_odom_to_base = tf2_buffer->lookupTransform("odom", "base_link", time );
} catch (const tf::TransformException& ex){
} catch (const tf2::TransformException& ex){
ROS_ERROR("NAO Footprint error %s",ex.what());
return ;
}
Expand Down

0 comments on commit a83ec33

Please sign in to comment.