git commit -m "first commit for v2"
This commit is contained in:
66
Devices/Packages/msle_tf_base_link/src/mlse_tf_base_link_broadcaster.cpp
Executable file
66
Devices/Packages/msle_tf_base_link/src/mlse_tf_base_link_broadcaster.cpp
Executable file
@@ -0,0 +1,66 @@
|
||||
#include <ros/ros.h>
|
||||
#include <tf2/LinearMath/Quaternion.h>
|
||||
#include <tf2_ros/transform_broadcaster.h>
|
||||
#include <geometry_msgs/TransformStamped.h>
|
||||
#include <sick_line_guidance/MLS_Measurement.h>
|
||||
#include <std_msgs/UInt8MultiArray.h>
|
||||
|
||||
template<class T> static T readMember(XmlRpc::XmlRpcValue & value, const std::string & member, const T & defaultvalue)
|
||||
{
|
||||
if(value.hasMember(member))
|
||||
return value[member];
|
||||
return defaultvalue;
|
||||
}
|
||||
|
||||
|
||||
std_msgs::UInt8MultiArray measurement_array;
|
||||
|
||||
void msleCallback(const sick_line_guidance::MLS_MeasurementConstPtr& msg)
|
||||
{
|
||||
if(((msg->lcp & 0x02) >> 1) == 0x01)
|
||||
{
|
||||
static tf2_ros::TransformBroadcaster br;
|
||||
geometry_msgs::TransformStamped transformStamped;
|
||||
int sign = msg->header.frame_id[0] == 'f' ? 1 : -1;
|
||||
|
||||
transformStamped.header.stamp = ros::Time::now();
|
||||
transformStamped.header.frame_id = "base_link";
|
||||
transformStamped.child_frame_id = msg->header.frame_id;
|
||||
transformStamped.transform.translation.x = sign * 0.476;
|
||||
transformStamped.transform.translation.y = msg->position[1];
|
||||
transformStamped.transform.translation.z = 0.0;
|
||||
tf2::Quaternion q;
|
||||
q.setRPY(0, 0, 0);
|
||||
transformStamped.transform.rotation.x = q.x();
|
||||
transformStamped.transform.rotation.y = q.y();
|
||||
transformStamped.transform.rotation.z = q.z();
|
||||
transformStamped.transform.rotation.w = q.w();
|
||||
br.sendTransform(transformStamped);
|
||||
}
|
||||
}
|
||||
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
/* Khoi tao Node */
|
||||
ros::init(argc, argv, "mlse_base_link_broadcaster");
|
||||
ros::NodeHandlePtr nh = boost::make_shared<ros::NodeHandle>();
|
||||
std::string node_name = ros::this_node::getName();
|
||||
ROS_INFO("%s.cpp-node_name: %s", node_name.c_str(), node_name.c_str());
|
||||
XmlRpc::XmlRpcValue nodes;
|
||||
if(!nh->getParam(node_name + "/nodes", nodes) || nodes.size() < 1)
|
||||
{
|
||||
ROS_ERROR("%s: no driver found in yaml-file, please check configuration. Aborting...", node_name.c_str());
|
||||
return 1;
|
||||
}
|
||||
std::vector<ros::Subscriber> mlse_subscribers;
|
||||
for(XmlRpc::XmlRpcValue::iterator object_iter = nodes.begin(); object_iter != nodes.end(); ++object_iter)
|
||||
{
|
||||
std::string topic_name = readMember<std::string>(object_iter->second, "sick_topic", "");
|
||||
int subscribe_queue_size = readMember<int>(object_iter->second, "subscribe_queue_size", 1);
|
||||
ROS_INFO("%s: initializing toppic \"%s\" queue_size \"%d\"...", node_name.c_str(), topic_name.c_str(), subscribe_queue_size);
|
||||
ros::Subscriber sub = nh->subscribe(topic_name, subscribe_queue_size, &msleCallback);
|
||||
mlse_subscribers.push_back(sub);
|
||||
}
|
||||
ros::spin();
|
||||
return 0;
|
||||
}
|
||||
Reference in New Issue
Block a user