minimal_test.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement
4  *
5  * Copyright (c) 2018, Simbe Robotics, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Simbe Robotics, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Steve Macenski (steven.macenski@simberobotics.com)
36  * Purpose: Test minimum configuration of costmap_2d
37 /*********************************************************************/
38 
39 
40 #include <ros/ros.h>
43 #include <thread>
44 
45 
46 /*****************************************************************************/
48 /*****************************************************************************/
49 {
51  tf::Transform transform;
52  transform.setIdentity();
53  transform.setOrigin(tf::Vector3(2.,2.,0.));
54 
55  ros::Rate r(20);
56  while (ros::ok())
57  {
59  "/map", "/base_link"));
61  "/base_link", "/camera_link"));
62  r.sleep();
63  ros::spinOnce();
64  }
65 }
66 
67 /*****************************************************************************/
68 int main(int argc, char **argv)
69 /*****************************************************************************/
70 {
71  ros::init(argc, argv, "STVL_minimal_test");
72 
74 
75  std::thread t(TransformThread);
76 
77  costmap_2d::Costmap2DROS costmap("global_costmap", tf);
78  costmap.start();
79 
80  ros::Rate r(10);
81  while (ros::ok())
82  {
83  // then make a thread to do something with a costmap pointer...
84  ros::spinOnce();
85  r.sleep();
86  }
87  return 1;
88 }
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void TransformThread()
void setIdentity()
ROSCPP_DECL bool ok()
void sendTransform(const StampedTransform &transform)
bool sleep()
static Time now()
ROSCPP_DECL void spinOnce()
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)


spatio_temporal_voxel_layer
Author(s):
autogenerated on Sat Dec 21 2019 04:06:19