joint_tf_publisher.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2015-2017, the ypspur_ros authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <ros/ros.h>
31 
32 #include <geometry_msgs/TransformStamped.h>
33 #include <sensor_msgs/JointState.h>
34 
36 
37 #include <signal.h>
38 #include <sys/types.h>
39 #include <sys/wait.h>
40 #include <map>
41 #include <string>
42 
43 #include <compatibility.h>
44 
46 {
47 private:
50  std::map<std::string, ros::Subscriber> subs_;
52 
53  void cbJoint(const sensor_msgs::JointState::ConstPtr& msg)
54  {
55  for (size_t i = 0; i < msg->name.size(); i++)
56  {
57  geometry_msgs::TransformStamped trans;
58  trans.header = msg->header;
59  trans.header.frame_id = msg->name[i] + "_in";
60  trans.child_frame_id = msg->name[i] + "_out";
61  trans.transform.rotation = tf::createQuaternionMsgFromYaw(msg->position[i]);
62  tf_broadcaster_.sendTransform(trans);
63  }
64  }
65 
66 public:
68  : nh_()
69  , pnh_("~")
70  {
71  subs_["joint"] = compat::subscribe(
72  nh_, "joint_states",
73  pnh_, "joint", 1, &JointTfPublisherNode::cbJoint, this);
74  }
75 };
76 
77 int main(int argc, char* argv[])
78 {
79  ros::init(argc, argv, "joint_tf_publisher");
80 
82  ros::spin();
83 
84  return 0;
85 }
int main(int argc, char *argv[])
tf::TransformBroadcaster tf_broadcaster_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::map< std::string, ros::Subscriber > subs_
ROSCPP_DECL void spin(Spinner &spinner)
void sendTransform(const StampedTransform &transform)
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
void cbJoint(const sensor_msgs::JointState::ConstPtr &msg)
ros::Subscriber subscribe(ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, void(T::*fp)(M) const, T *obj, const ros::TransportHints &transport_hints=ros::TransportHints())
Definition: compatibility.h:98


ypspur_ros
Author(s): Atsushi Watanabe
autogenerated on Thu Jun 6 2019 19:41:30