ros_mac_authentication.cpp
Go to the documentation of this file.
1 
14 #include <fstream>
15 #include <openssl/sha.h>
16 #include <ros/ros.h>
17 #include <rosauth/Authentication.h>
18 #include <sstream>
19 #include <string>
20 
21 using namespace std;
22 using namespace ros;
23 
29 #define SECRET_FILE_PARAM "/ros_mac_authentication/secret_file_location"
30 
35 #define MISSING_PARAMETER -1
36 
41 #define FILE_IO_ERROR -2
42 
47 #define INVALID_SECRET -3
48 
53 #define SECRET_LENGTH 16
54 
55 // the secret string used in the MAC
56 string secret;
57 
58 bool authenticate(rosauth::Authentication::Request &req, rosauth::Authentication::Response &res)
59 {
60  // keep track of the current time
61  Time t = Time::now();
62  // clocks can be out of sync, check which comes later
63  Duration *diff;
64  if (req.t > t)
65  diff = new Duration(req.t - t);
66  else
67  diff = new Duration(t - req.t);
68  bool time_check = diff->sec < 5 && req.end > t;
69  delete diff;
70 
71  // check if we pass the time requirement
72  if (time_check)
73  {
74  // create the string to hash
75  stringstream ss;
76  ss << secret << req.client << req.dest << req.rand << req.t.sec << req.level << req.end.sec;
77  string local_hash = ss.str();
78 
79  // check the request
80  unsigned char sha512_hash[SHA512_DIGEST_LENGTH];
81  SHA512((unsigned char *)local_hash.c_str(), local_hash.length(), sha512_hash);
82 
83  // convert to a hex string to compare
84  char hex[SHA512_DIGEST_LENGTH * 2];
85  for (int i = 0; i < SHA512_DIGEST_LENGTH; i++)
86  sprintf(&hex[i * 2], "%02x", sha512_hash[i]);
87 
88  // an authenticated user must match the MAC string
89  res.authenticated = (strcmp(hex, req.mac.c_str()) == 0);
90  }
91  else
92  res.authenticated = false;
93 
94  return true;
95 }
96 
104 int main(int argc, char **argv)
105 {
106  // initialize ROS and the node
107  init(argc, argv, "ros_mac_authentication");
108  NodeHandle node;
109 
110  // check if we have to check the secret file
111  string file;
112  if (!node.getParam(SECRET_FILE_PARAM, file))
113  {
114  ROS_ERROR("Parameter '%s' not found.", SECRET_FILE_PARAM);
115  return MISSING_PARAMETER;
116  }
117  else
118  {
119  // try and load the file
120  ifstream f;
121  f.open(file.c_str(), ifstream::in);
122  if (f.is_open())
123  {
124  // should be a 1 line file with the string
125  getline(f, secret);
126  f.close();
127  // check the length of the secret
128  if (secret.length() != SECRET_LENGTH)
129  {
130  ROS_ERROR("Secret string not of length %d.", SECRET_LENGTH);
131  return INVALID_SECRET;
132  }
133  else
134  {
135  ServiceServer service = node.advertiseService("authenticate", authenticate);
136  ROS_INFO("ROS Authentication Server Started");
137  spin();
138 
139  return EXIT_SUCCESS;
140  }
141  }
142  else
143  {
144  ROS_ERROR("Could not read from file '%s'", file.c_str());
145  return FILE_IO_ERROR;
146  }
147  }
148 }
#define INVALID_SECRET
f
void init(const M_string &remappings)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
#define FILE_IO_ERROR
#define MISSING_PARAMETER
#define ROS_INFO(...)
string secret
ROSCPP_DECL void spin()
bool getParam(const std::string &key, std::string &s) const
#define SECRET_LENGTH
int main(int argc, char **argv)
bool authenticate(rosauth::Authentication::Request &req, rosauth::Authentication::Response &res)
#define ROS_ERROR(...)
#define SECRET_FILE_PARAM


rosauth
Author(s): Russell Toris
autogenerated on Wed Jun 5 2019 20:18:45