rviz_rh_pub.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2018 ROBOTIS CO., LTD.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *******************************************************************************/
16 
17 #include <ros/ros.h>
18 #include <sensor_msgs/JointState.h>
19 
22 
23 void presentJointStatesCallback(const sensor_msgs::JointState::ConstPtr& msg)
24 {
25  sensor_msgs::JointState present_msg;
26 
27  for (int index = 0; index < msg->name.size(); index++)
28  {
29  present_msg.name.push_back(msg->name[index]);
30  present_msg.position.push_back(msg->position[index]);
31 
32  if (present_msg.name[index] == "rh_p12_rn")
33  {
34  present_msg.name.push_back("rh_r2");
35  present_msg.position.push_back(present_msg.position[index] * (1.0 / 1.1));
36  present_msg.name.push_back("rh_l1");
37  present_msg.position.push_back(present_msg.position[index]);
38  present_msg.name.push_back("rh_l2");
39  present_msg.position.push_back(present_msg.position[index] * (1.0 / 1.1));
40  }
41  }
42  g_present_joint_states_pub.publish(present_msg);
43 }
44 
45 void goalJointStatesCallback(const sensor_msgs::JointState::ConstPtr& msg)
46 {
47  sensor_msgs::JointState goal_msg;
48 
49  for (int index = 0; index < msg->name.size(); index++)
50  {
51  goal_msg.name.push_back(msg->name[index]);
52  goal_msg.position.push_back(msg->position[index]);
53 
54  if (goal_msg.name[index] == "rh_p12_rn")
55  {
56  goal_msg.name.push_back("rh_r2");
57  goal_msg.position.push_back(goal_msg.position[index] * (1.0 / 1.1));
58  goal_msg.name.push_back("rh_l1");
59  goal_msg.position.push_back(goal_msg.position[index]);
60  goal_msg.name.push_back("rh_l2");
61  goal_msg.position.push_back(goal_msg.position[index] * (1.0 / 1.1));
62  }
63  }
64  g_goal_joint_states_pub.publish(goal_msg);
65 }
66 
67 int main(int argc, char **argv)
68 {
69  ros::init(argc, argv, "rviz_rh_p12_rn_publisher");
70  ros::NodeHandle nh("~");
71 
72  g_present_joint_states_pub = nh.advertise<sensor_msgs::JointState>("/robotis/rh_p12_rn/present_joint_states", 0);
73  g_goal_joint_states_pub = nh.advertise<sensor_msgs::JointState>("/robotis/rh_p12_rn/goal_joint_states", 0);
74 
75  ros::Subscriber present_joint_states_sub = nh.subscribe("/robotis/present_joint_states", 5, presentJointStatesCallback);
76  ros::Subscriber goal_joint_states_sub = nh.subscribe("/robotis/goal_joint_states", 5, goalJointStatesCallback);
77 
78  ros::spin();
79 
80  return 0;
81 }
ros::Publisher g_goal_joint_states_pub
Definition: rviz_rh_pub.cpp:21
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
void goalJointStatesCallback(const sensor_msgs::JointState::ConstPtr &msg)
Definition: rviz_rh_pub.cpp:45
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void presentJointStatesCallback(const sensor_msgs::JointState::ConstPtr &msg)
Definition: rviz_rh_pub.cpp:23
ros::Publisher g_present_joint_states_pub
Definition: rviz_rh_pub.cpp:20
int main(int argc, char **argv)
Definition: rviz_rh_pub.cpp:67


rh_p12_rn_description
Author(s): SCH
autogenerated on Mon Jun 10 2019 14:42:08