5 #include <pcl/point_cloud.h> 6 #include <pcl/point_types.h> 9 #include <dynamic_reconfigure/server.h> 10 #include <sick_scan/tf_dynConfig.h> 41 void callback(sick_scan_fusion::tf_dynConfig &config, uint32_t level)
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;
54 int main (
int argc,
char** argv)
57 ros::init (argc, argv,
"sick_scan_fusion_tf_dyn");
66 dynamic_reconfigure::Server<sick_scan_fusion::tf_dynConfig> server;
67 dynamic_reconfigure::Server<sick_scan_fusion::tf_dynConfig>::CallbackType
f;
69 server.setCallback(f);
92 transform_base_trans.header.frame_id = cfgTrans.
parentFrame;
93 transform_base_trans.child_frame_id = cfgTrans.
childFrame;
95 transform_base_trans.header.seq = seq;
96 br.sendTransform(transform_base_trans);
Eigen::Affine3d child_2_parent
int main(int argc, char **argv)
tf2_ros::Buffer tf_buffer
geometry_msgs::TransformStamped eigenToTransform(const Eigen::Affine3d &T)
Eigen::Vector4f max_point
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Eigen::Vector4f min_point
void callback(sick_scan_fusion::tf_dynConfig &config, uint32_t level)
ROSCPP_DECL void spinOnce()