YARP
Yet Another Robot Platform
Server.cpp
Go to the documentation of this file.
1 /*
2  * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3  * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium
4  * SPDX-License-Identifier: BSD-3-Clause
5  */
6 
8 
9 #include <yarp/os/Bottle.h>
10 #include <yarp/os/Contact.h>
11 #include <yarp/os/Port.h>
12 #include <yarp/os/Property.h>
13 #include <yarp/os/SystemClock.h>
14 #include <yarp/os/Log.h>
15 #include <yarp/os/LogStream.h>
21 
22 #include <cstdio>
23 #include <cmath>
24 
25 using yarp::os::Bottle;
26 using yarp::os::Contact;
27 using yarp::os::Port;
28 using yarp::os::Property;
34 
35 YARP_SERVERSQL_LOG_COMPONENT(SERVER, "yarp.serversql.Server")
36 
37 
38 int yarp::serversql::Server::run(int argc, char** argv)
39 {
40  Property options;
41  options.fromCommand(argc, argv, false);
42 
43  bool verbose = options.check("verbose");
44  bool silent = options.check("silent");
45 
46  if (verbose) {
48  } else if (silent) {
50  }
51 
52  yCInfo(SERVER, R"===(
53  ==========================
54  | __ __ ___ ____ ____ |
55  | \ \/ // || _ \ | _ \ |
56  | \ // /| || |/ / | |/ / |
57  | / // ___ || _ \ | _/ |
58  | /_//_/ |_||_| \_\|_| |
59  | |
60  ==========================)===");
61  yCInfo(SERVER);
62 
63  if (options.check("help")) {
64  yCInfo(SERVER, "Welcome to the YARP name server.\n");
65  yCInfo(SERVER, " --write Write IP address and socket on the configuration file.\n");
66  yCInfo(SERVER, " --config filename.conf Load options from a file.\n");
67  yCInfo(SERVER, " --portdb ports.db Store port information in named database.\n");
68  yCInfo(SERVER, " Must not be on an NFS file system.\n");
69  yCInfo(SERVER, " Set to :memory: to store in memory (faster).\n");
70  yCInfo(SERVER, " --subdb subs.db Store subscription information in named database.\n");
71  yCInfo(SERVER, " Must not be on an NFS file system.\n");
72  yCInfo(SERVER, " Set to :memory: to store in memory (faster).\n");
73  yCInfo(SERVER, " --ip IP.AD.DR.ESS Set IP address of server.\n");
74  yCInfo(SERVER, " --socket NNNNN Set port number of server.\n");
75  yCInfo(SERVER, " --web dir Serve web resources from given directory.\n");
76  yCInfo(SERVER, " --no-web-cache Reload pages from file for each request.\n");
77  yCInfo(SERVER, " --ros Delegate pub/sub to ROS name server.\n");
78  yCInfo(SERVER, " --silent Start in silent mode.\n");
79  //this->stop();
80 
81  return 0;
82  } else {
83  yCInfo(SERVER, "Call with --help for information on available options\n");
84  }
85 
87  if (!nc.open(options)) {
88  return 1;
89  }
90 
91  bool ok = false;
92  NameServerManager name(nc);
93  BootstrapServer fallback(name);
94  Port server;
95  Contact alt;
96  Bottle cmd;
97  Bottle reply;
98  double messageCounter(0);
99  double pollingRate(.1);
100 
101  name.setPort(server);
102  server.setReaderCreator(name);
103 
104  ok = server.open(nc.where(),false);
105  if (!ok) {
106  yCError(SERVER, "Name server failed to open\n");
107  return 1;
108  }
109 
110  fallback.start();
111 
112 
113  // Repeat registrations for the server and fallback server -
114  // these registrations are more complete.
115  yCInfo(SERVER, "Registering name server with itself");
116  nc.preregister(nc.where());
117  nc.preregister(fallback.where());
118 
119  alt = nc.whereDelegate();
120 
121  if (alt.isValid()) {
122  nc.preregister(alt);
123  }
124  nc.goPublic();
125 
126  //Setting nameserver property
127  cmd.addString("set");
128  cmd.addString(server.getName());
129  cmd.addString("nameserver");
130  cmd.addString("true");
131 
132  NameClient::getNameClient().send(cmd, reply);
133 
134  yCInfo(SERVER, "Name server can be browsed at http:/%s",
135  nc.where().toURI(false).c_str());
136  yCInfo(SERVER, "Ok. Ready!");
137 
138  while(!shouldStop) {
139  messageCounter += pollingRate;
140  SystemClock::delaySystem(pollingRate);
141  double dummy;
142 
143  if(std::modf(messageCounter / 600.0, &dummy) < .00001) {
144  yCInfo(SERVER, "Name server running happily");
145  }
146  }
147 
148  yCInfo(SERVER, "closing yarp server");
149  server.close();
150  return 0;
151 }
const yarp::os::LogComponent & SERVER()
Definition: Server.cpp:35
Multicast and file-based mechanisms for finding the name server.
Manage the name server.
void setPort(yarp::os::Port &port)
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:74
void addString(const char *str)
Places a string in the bottle, at the end of the list.
Definition: Bottle.cpp:170
Represents how to reach a part of a YARP network.
Definition: Contact.h:36
bool isValid() const
Checks if a Contact is tagged as valid.
Definition: Contact.cpp:298
std::string toURI(bool includeCarrier=true) const
Get a representation of the Contact as a URI.
Definition: Contact.cpp:313
virtual std::string getName() const
Get name of port.
Definition: Contactable.cpp:14
@ DebugType
Definition: Log.h:75
@ WarningType
Definition: Log.h:77
A mini-server for network communication.
Definition: Port.h:47
void setReaderCreator(PortReaderCreator &creator)
Set a creator for readers for port data.
Definition: Port.cpp:516
void close() override
Stop port activity.
Definition: Port.cpp:354
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
Definition: Port.cpp:79
A class for storing options and configuration information.
Definition: Property.h:34
bool check(const std::string &key) const override
Check if there exists a property of the given name.
Definition: Property.cpp:1041
void fromCommand(int argc, char *argv[], bool skipFirst=true, bool wipe=true)
Interprets a list of command arguments as a list of properties.
Definition: Property.cpp:1074
Client for YARP name server.
Definition: NameClient.h:32
bool open(yarp::os::Searchable &options)
void preregister(const yarp::os::Contact &c)
#define yCInfo(component,...)
Definition: LogComponent.h:132
#define yCError(component,...)
Definition: LogComponent.h:154
#define YARP_SERVERSQL_LOG_COMPONENT(name, name_string)
Definition: LogComponent.h:34
void setMinumumLogType(yarp::os::Log::LogType minumumLogType)
The main, catch-all namespace for YARP.
Definition: dirs.h:16