publisher.cc
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Hunter Allen <hunter.allen@vanderbilt.edu>
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #include <string>
36 #include <ros/ros.h>
37 #include <sensor_msgs/JointState.h>
40 
41 int main( int argc, char* argv[] )
42 {
43  ros::init(argc, argv, "state_publisher" );
45 
46  ros::Publisher joint_state_publisher = n.advertise<sensor_msgs::JointState>("joint_states",1000);
47 
48  tf::TransformBroadcaster broadcaster;
49  ros::Rate loop_rate(30);
50 
51  // message declarations
52  geometry_msgs::TransformStamped odom_trans;
53  sensor_msgs::JointState joint_state;
54  //odom_trans.header.frame_id = "base_link";
55  //odom_trans.child_frame_id = "";
56 
57  while (ros::ok())
58  {
59  joint_state.header.stamp = ros::Time::now();
60  joint_state.name.resize(6); //Pioneer has 6 joint state definitions.
61  joint_state.position.resize(6);
62 
63  joint_state.name[0] = "base_top_joint";
64  joint_state.position[0] = 0;
65 
66  joint_state.name[1] = "base_swivel_joint";
67  joint_state.position[1] = 0;
68 
69  joint_state.name[2] = "swivel_hubcap_joint";
70  joint_state.position[2] = 0;
71 
72  joint_state.name[3] = "center_wheel_joint";
73  joint_state.position[3] = 0;
74 
75  joint_state.name[4] = "base_front_joint";
76  joint_state.position[4] = 0;
77 
78  joint_state.name[5] = "base_back_joint";
79  joint_state.position[5] = 0;
80 
81  //odom_trans.header.stamp = ros::Time::now();
82  //send the joint state information
83  joint_state_publisher.publish(joint_state);
84  //broadcaster.sendTransform(odom_trans);
85 
86  //adjust loop each iteration.
87  loop_rate.sleep();
88  }//the things ros will do
89 
90  return 0;
91 }//end main
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int main(int argc, char *argv[])
Definition: publisher.cc:41
bool sleep()
static Time now()


p2os_urdf
Author(s): Hunter L. Allen , David Feil-Seifer , Brian Gerkey, Kasper Stoy, Richard Vaughan, Andrew Howard, Tucker Hermans, ActivMedia Robotics LLC, MobileRobots Inc.
autogenerated on Sat Jun 20 2020 03:29:47