sensor_alignment_tf_dyn.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 
3 // PCL specific includes
5 #include <pcl/point_cloud.h>
6 #include <pcl/point_types.h>
7 #include <pcl_ros/transforms.h>
8 
10 #include <sick_scan/tf_dynConfig.h>
11 
12 #include <tf2/LinearMath/Quaternion.h>
13 #include <tf2_ros/transform_broadcaster.h>
14 #include <tf2_eigen/tf2_eigen.h>
15 
16 Eigen::Affine3d child_2_parent;
17 
19 {
20 public:
21  std::string parentFrame;
22  std::string childFrame;
23  double trans_x;
24  double trans_y;
25  double trans_z;
26  double trans_rot_x;
27  double trans_rot_y;
28  double trans_rot_z;
29 };
30 
32 
33 
34 // for setting region of interest
35 Eigen::Vector4f min_point;
36 Eigen::Vector4f max_point;
37 
39 
40 
41 void callback(sick_scan_fusion::tf_dynConfig &config, uint32_t level)
42 {
43  cfgTrans.parentFrame = config.parent_frame;
44  cfgTrans.childFrame = config.child_frame;
45 
46  cfgTrans.trans_x = config.tf_x;
47  cfgTrans.trans_y = config.tf_y;
48  cfgTrans.trans_z = config.tf_z;
49  cfgTrans.trans_rot_x = config.tf_rot_x * M_PI / 180.0;
50  cfgTrans.trans_rot_y = config.tf_rot_y * M_PI / 180.0;
51  cfgTrans.trans_rot_z = config.tf_rot_z * M_PI / 180.0;
52  }
53 
54 int main (int argc, char** argv)
55 {
56  // initialize
57  ros::init (argc, argv, "sick_scan_fusion_tf_dyn");
58  ros::NodeHandle nh;
59 
61 
62 
63  child_2_parent = Eigen::Affine3d::Identity();
64 
65  // dynamic reconfigure
68  // f = std::bind(&callback, _1, _2);
69  f = std::bind(&callback, std::placeholders::_1, std::placeholders::_2);
70  server.setCallback(f);
71 
72 
73  unsigned seq= 0;
74  ros::Rate loop_rate(100);
75  while (ros::ok())
76  {
77  if ((seq % 20) == 0)
78  {
79  printf("Par. %s Child: %s Trans x: %0.3lf\n", cfgTrans.childFrame.c_str(), cfgTrans.parentFrame.c_str(), cfgTrans.trans_x);
81  child_2_parent = Eigen::Affine3d::Identity();
82  child_2_parent.translate(Eigen::Vector3d( cfgTrans.trans_x,0,0));
83  child_2_parent.translate(Eigen::Vector3d(0, cfgTrans.trans_y,0));
84  child_2_parent.translate(Eigen::Vector3d(0, 0, cfgTrans.trans_z));
85  // pitch
86  child_2_parent.rotate(Eigen::AngleAxisd(cfgTrans.trans_rot_x, Eigen::Vector3d(1, 0, 0)));
87  // yaw
88  child_2_parent.rotate(Eigen::AngleAxisd(cfgTrans.trans_rot_y, Eigen::Vector3d(0, 1, 0)));
89  // yaw
90  child_2_parent.rotate(Eigen::AngleAxisd(cfgTrans.trans_rot_z, Eigen::Vector3d(0, 0, 1)));
91 
92  geometry_msgs::TransformStamped transform_base_trans = tf2::eigenToTransform(child_2_parent);
93  transform_base_trans.header.frame_id = cfgTrans.parentFrame;
94  transform_base_trans.child_frame_id = cfgTrans.childFrame;
95  transform_base_trans.header.stamp = ros::Time::now();
96  transform_base_trans.header.seq = seq;
97  br.sendTransform(transform_base_trans);
98 
99  ros::spinOnce();
100  loop_rate.sleep();
101  ++seq;
102  }
103 }
104 
std_msgs::Header_::stamp
_stamp_type stamp
Definition: Header.h:45
geometry_msgs::TransformStamped_::header
_header_type header
Definition: TransformStamped.h:44
min_point
Eigen::Vector4f min_point
Definition: sensor_alignment_tf_dyn.cpp:35
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
alternate ROS initialization function.
ConfigTrans::trans_z
double trans_z
Definition: sensor_alignment_tf_dyn.cpp:25
ros::spinOnce
ROSCPP_DECL void spinOnce()
Process a single round of callbacks.
Definition: rossimu.cpp:255
ConfigTrans
Definition: sensor_alignment_tf_dyn.cpp:18
ros::ok
ROSCPP_DECL bool ok()
Check whether it's time to exit.
Definition: rossimu.cpp:273
tf_buffer
tf2_ros::Buffer tf_buffer
Definition: sensor_alignment_tf_dyn.cpp:38
ConfigTrans::trans_rot_x
double trans_rot_x
Definition: sensor_alignment_tf_dyn.cpp:26
f
f
tf2_ros::TransformListener
This class provides an easy way to request and receive coordinate frame transform information.
Definition: transform_listener.h:49
geometry_msgs::TransformStamped_::child_frame_id
_child_frame_id_type child_frame_id
Definition: TransformStamped.h:47
tf2_ros::TransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
callback
void callback(sick_scan_fusion::tf_dynConfig &config, uint32_t level)
Definition: sensor_alignment_tf_dyn.cpp:41
ConfigTrans::trans_x
double trans_x
Definition: sensor_alignment_tf_dyn.cpp:23
std_msgs::Header_::seq
_seq_type seq
Definition: Header.h:42
tf2_ros::Buffer
Standard implementation of the tf2_ros::BufferInterface abstract data type.
Definition: buffer.h:52
dynamic_reconfigure::Server::CallbackType
std::function< void(ConfigType &, uint32_t level)> CallbackType
Definition: server.h:84
ConfigTrans::parentFrame
std::string parentFrame
Definition: sensor_alignment_tf_dyn.cpp:21
sick_scan_fusion::tf_dynConfig
Definition: tf_dynConfig.h:33
ros::Rate::sleep
bool sleep()
ConfigTrans::childFrame
std::string childFrame
Definition: sensor_alignment_tf_dyn.cpp:22
ConfigTrans::trans_rot_z
double trans_rot_z
Definition: sensor_alignment_tf_dyn.cpp:28
std_msgs::Header_::frame_id
_frame_id_type frame_id
Definition: Header.h:48
ConfigTrans::trans_rot_y
double trans_rot_y
Definition: sensor_alignment_tf_dyn.cpp:27
main
int main(int argc, char **argv)
Definition: sensor_alignment_tf_dyn.cpp:54
tf2_ros::TransformBroadcaster
This class provides an easy way to publish coordinate frame transform information....
Definition: transform_broadcaster.h:49
dynamic_reconfigure::Server
Definition: server.h:65
ros::Rate
ConfigTrans::trans_y
double trans_y
Definition: sensor_alignment_tf_dyn.cpp:24
pcl_conversions.h
cfgTrans
ConfigTrans cfgTrans
Definition: sensor_alignment_tf_dyn.cpp:31
server.h
max_point
Eigen::Vector4f max_point
Definition: sensor_alignment_tf_dyn.cpp:36
child_2_parent
Eigen::Affine3d child_2_parent
Definition: sensor_alignment_tf_dyn.cpp:16
config
config
geometry_msgs::TransformStamped_
Definition: TransformStamped.h:25
test_server.server
server
Definition: test_server.py:219
ros::NodeHandle
ros::Time::now
static Time now()


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:10