urg_sim_exec.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2024 The urg_stamped Authors
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 <iostream>
18 #include <string>
19 #include <vector>
20 
21 #include <boost/asio/ip/tcp.hpp>
22 
23 #include <urg_sim/urg_sim.h>
24 
25 int main(int argc, char** argv)
26 {
27  const urg_sim::URGSimulator::Params params_uust1 =
28  {
30  .boot_duration = 0.5,
31  .comm_delay_base = 0.0004,
32  .comm_delay_sigma = 0.00005,
33  .scan_interval = 0.02505,
34  .clock_rate = 1.00005,
35  .hex_ii_timestamp = false,
36  .angle_resolution = 1440,
37  .angle_min = 0,
38  .angle_max = 1080,
39  .angle_front = 540,
40  };
41  const urg_sim::URGSimulator::Params params_uust2 =
42  {
44  .boot_duration = 0.5,
45  .comm_delay_base = 0.0004,
46  .comm_delay_sigma = 0.00005,
47  .scan_interval = 0.02505,
48  .clock_rate = 1.00005,
49  .hex_ii_timestamp = false,
50  .angle_resolution = 1440,
51  .angle_min = 0,
52  .angle_max = 1080,
53  .angle_front = 540,
54  };
55  const urg_sim::URGSimulator::Params params_utm =
56  {
58  .boot_duration = 2.0,
59  .comm_delay_base = 0.0005,
60  .comm_delay_sigma = 0.0004,
61  .scan_interval = 0.02505,
62  .clock_rate = 1.00005,
63  .hex_ii_timestamp = false,
64  .angle_resolution = 1440,
65  .angle_min = 0,
66  .angle_max = 1080,
67  .angle_front = 540,
68  };
69 
71 
72  if (argc < 1 || std::string(argv[1]) == "UTM")
73  {
74  params = params_utm;
75  std::cerr << "Using UTM model" << std::endl;
76  }
77  else if (std::string(argv[1]) == "UST" || std::string(argv[1]) == "UUST1")
78  {
79  params = params_uust1;
80  std::cerr << "Using UST (UUST1) model" << std::endl;
81  }
82  else if (std::string(argv[1]) == "UUST2")
83  {
84  params = params_uust2;
85  std::cerr << "Using UST (UUST2) model" << std::endl;
86  }
87  else
88  {
89  std::cerr << "Unknown model: " << argv[1] << std::endl;
90  return 1;
91  }
92 
94  boost::asio::ip::tcp::endpoint(
95  boost::asio::ip::tcp::v4(),
96  10940),
97  params);
98  std::cerr
99  << "Listening on :" << sim.getLocalEndpoint().port()
100  << std::endl;
101 
102  sim.spin();
103 
104  return 1;
105 }
urg_sim::URGSimulator::Params
Definition: urg_sim.h:68
urg_sim::URGSimulator
Definition: urg_sim.h:59
main
int main(int argc, char **argv)
Definition: urg_sim_exec.cpp:25
urg_sim::URGSimulator::Model::UTM
@ UTM
urg_sim::URGSimulator::Model::UST_UUST2
@ UST_UUST2
urg_sim::URGSimulator::Model::UST_UUST1
@ UST_UUST1
urg_sim::URGSimulator::Params::model
Model model
Definition: urg_sim.h:70
params
std::vector< urg_sim::URGSimulator::Params > params({ { .model=urg_sim::URGSimulator::Model::UTM,.boot_duration=0.01,.comm_delay_base=0.0002,.comm_delay_sigma=0.0004,.scan_interval=0.02505,.clock_rate=1.0,.hex_ii_timestamp=false,.angle_resolution=1440,.angle_min=0,.angle_max=1080,.angle_front=540, }, { .model=urg_sim::URGSimulator::Model::UTM,.boot_duration=0.01,.comm_delay_base=0.0002,.comm_delay_sigma=0.0004,.scan_interval=0.02505,.clock_rate=1.001,.hex_ii_timestamp=false,.angle_resolution=1440,.angle_min=0,.angle_max=1080,.angle_front=540, }, { .model=urg_sim::URGSimulator::Model::UTM,.boot_duration=0.01,.comm_delay_base=0.0002,.comm_delay_sigma=0.0004,.scan_interval=0.02505,.clock_rate=0.999,.hex_ii_timestamp=false,.angle_resolution=1440,.angle_min=0,.angle_max=1080,.angle_front=540, }, { .model=urg_sim::URGSimulator::Model::UST_UUST1,.boot_duration=0.01,.comm_delay_base=0.0005,.comm_delay_sigma=0.0005,.scan_interval=0.02505,.clock_rate=1.0,.hex_ii_timestamp=true,.angle_resolution=1440,.angle_min=0,.angle_max=1080,.angle_front=540, }, { .model=urg_sim::URGSimulator::Model::UST_UUST1,.boot_duration=0.01,.comm_delay_base=0.0005,.comm_delay_sigma=0.0005,.scan_interval=0.02505,.clock_rate=1.001,.hex_ii_timestamp=true,.angle_resolution=1440,.angle_min=0,.angle_max=1080,.angle_front=540, }, { .model=urg_sim::URGSimulator::Model::UST_UUST1,.boot_duration=0.01,.comm_delay_base=0.0005,.comm_delay_sigma=0.0005,.scan_interval=0.02505,.clock_rate=0.999,.hex_ii_timestamp=true,.angle_resolution=1440,.angle_min=0,.angle_max=1080,.angle_front=540, }, { .model=urg_sim::URGSimulator::Model::UST_UUST2,.boot_duration=0.01,.comm_delay_base=0.0002,.comm_delay_sigma=0.0002,.scan_interval=0.02505,.clock_rate=1.0,.hex_ii_timestamp=true,.angle_resolution=1440,.angle_min=0,.angle_max=1080,.angle_front=540, }, { .model=urg_sim::URGSimulator::Model::UST_UUST2,.boot_duration=0.01,.comm_delay_base=0.0002,.comm_delay_sigma=0.0002,.scan_interval=0.02505,.clock_rate=1.001,.hex_ii_timestamp=true,.angle_resolution=1440,.angle_min=0,.angle_max=1080,.angle_front=540, }, { .model=urg_sim::URGSimulator::Model::UST_UUST2,.boot_duration=0.01,.comm_delay_base=0.0002,.comm_delay_sigma=0.0002,.scan_interval=0.02505,.clock_rate=0.999,.hex_ii_timestamp=true,.angle_resolution=1440,.angle_min=0,.angle_max=1080,.angle_front=540, }, })
urg_sim::URGSimulator::getLocalEndpoint
boost::asio::ip::tcp::endpoint getLocalEndpoint() const
Definition: urg_sim.h:144
urg_sim::URGSimulator::spin
void spin()
Definition: urg_sim.cpp:779
urg_sim.h


urg_stamped
Author(s): Atsushi Watanabe
autogenerated on Wed Dec 18 2024 03:10:57