schunk_powercube_chain.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
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 
18 //##################
19 //#### includes ####
20 //##################
21 
22 // standard includes
23 // --
24 
25 // ROS includes
26 #include <ros/ros.h>
27 #include <urdf/model.h>
28 
29 // ROS message includes
30 #include <std_msgs/String.h>
31 #include <std_msgs/Float64MultiArray.h>
32 #include <sensor_msgs/JointState.h>
33 #include <trajectory_msgs/JointTrajectory.h>
34 #include <control_msgs/JointTrajectoryControllerState.h>
35 #include <diagnostic_msgs/DiagnosticArray.h>
36 
37 // ROS service includes
38 #include <std_srvs/Trigger.h>
39 #include <cob_srvs/SetString.h>
40 
41 // own includes
44 //#include <schunk_powercube_chain/Diagnostics.h>
45 
52 {
53 public:
57 
63 
67 
73 
76 
79 
82  bool stopped_;
83  bool error_;
84  std::string error_msg_;
86 
89  {
90  n_private_ = ros::NodeHandle("~");
91 
92  pc_params_ = new PowerCubeCtrlParams();
93  pc_ctrl_ = new PowerCubeCtrl(pc_params_);
94 
96  topicPub_JointState_ = n_.advertise<sensor_msgs::JointState>("joint_states", 1);
97  topicPub_ControllerState_ = n_.advertise<control_msgs::JointTrajectoryControllerState>("joint_trajectory_controller/state", 1);
98  topicPub_Diagnostic_ = n_.advertise<diagnostic_msgs::DiagnosticArray>("diagnostics", 1);
99 
101  topicSub_CommandPos_ = n_.subscribe("joint_group_position_controller/command", 1, &PowerCubeChainNode::topicCallback_CommandPos, this);
102  topicSub_CommandVel_ = n_.subscribe("joint_group_velocity_controller/command", 1, &PowerCubeChainNode::topicCallback_CommandVel, this);
103 
105  srvServer_Init_ = n_.advertiseService("driver/init", &PowerCubeChainNode::srvCallback_Init, this);
106  srvServer_Stop_ = n_.advertiseService("driver/stop", &PowerCubeChainNode::srvCallback_Stop, this);
107  srvServer_Recover_ = n_.advertiseService("driver/recover", &PowerCubeChainNode::srvCallback_Recover, this);
108  srvServer_SetOperationMode_ = n_.advertiseService("driver/set_operation_mode", &PowerCubeChainNode::srvCallback_SetOperationMode, this);
109  topicPub_OperationMode_ = n_.advertise<std_msgs::String>("driver/current_operationmode", 1);
110 
111  initialized_ = false;
112  stopped_ = true;
113  error_ = false;
114  last_publish_time_ = ros::Time::now();
115  }
116 
119  {
120  bool closed = pc_ctrl_->Close();
121  if (closed)
122  ROS_INFO("PowerCube Device closed!");
123  }
124 
129  {
131  std::string CanModule;
132  if (n_private_.hasParam("can_module"))
133  {
134  n_private_.getParam("can_module", CanModule);
135  }
136  else
137  {
138  ROS_ERROR("Parameter can_module not set, shutting down node...");
139  n_.shutdown();
140  }
141 
143  std::string CanDevice;
144  if (n_private_.hasParam("can_device"))
145  {
146  n_private_.getParam("can_device", CanDevice);
147  }
148  else
149  {
150  ROS_ERROR("Parameter can_device not set, shutting down node...");
151  n_.shutdown();
152  }
153 
155  int CanBaudrate;
156  if (n_private_.hasParam("can_baudrate"))
157  {
158  n_private_.getParam("can_baudrate", CanBaudrate);
159  }
160  else
161  {
162  ROS_ERROR("Parameter can_baudrate not set, shutting down node...");
163  n_.shutdown();
164  }
165 
167  XmlRpc::XmlRpcValue ModulIDsXmlRpc;
168  std::vector<int> ModulIDs;
169  if (n_private_.hasParam("modul_ids"))
170  {
171  n_private_.getParam("modul_ids", ModulIDsXmlRpc);
172  }
173  else
174  {
175  ROS_ERROR("Parameter modul_ids not set, shutting down node...");
176  n_.shutdown();
177  }
178 
180  bool UseMoveVel;
181  if (n_private_.hasParam("force_use_movevel"))
182  {
183  n_private_.getParam("force_use_movevel", UseMoveVel);
184  ROS_INFO("Parameter force_use_movevel set, using moveVel");
185  }
186  else
187  {
188  ROS_INFO("Parameter force_use_movevel not set, using moveStep");
189  UseMoveVel = false;
190  }
191  pc_params_->SetUseMoveVel(UseMoveVel);
192 
194  ModulIDs.resize(ModulIDsXmlRpc.size());
195  for (int i = 0; i < ModulIDsXmlRpc.size(); i++)
196  {
197  ModulIDs[i] = (int)ModulIDsXmlRpc[i];
198  }
199 
201  pc_params_->Init(CanModule, CanDevice, CanBaudrate, ModulIDs);
202 
204  XmlRpc::XmlRpcValue JointNamesXmlRpc;
205  std::vector<std::string> JointNames;
206  if (n_private_.hasParam("joint_names"))
207  {
208  n_private_.getParam("joint_names", JointNamesXmlRpc);
209  }
210  else
211  {
212  ROS_ERROR("Parameter joint_names not set, shutting down node...");
213  n_.shutdown();
214  }
215 
217  JointNames.resize(JointNamesXmlRpc.size());
218  for (int i = 0; i < JointNamesXmlRpc.size(); i++)
219  {
220  JointNames[i] = (std::string)JointNamesXmlRpc[i];
221  }
222 
224  if ((int)JointNames.size() != pc_params_->GetDOF())
225  {
226  ROS_ERROR("Wrong dimensions of parameter joint_names, shutting down node...");
227  n_.shutdown();
228  }
229  pc_params_->SetJointNames(JointNames);
230 
232  XmlRpc::XmlRpcValue MaxAccelerationsXmlRpc;
233  std::vector<double> MaxAccelerations;
234  if (n_private_.hasParam("max_accelerations"))
235  {
236  n_private_.getParam("max_accelerations", MaxAccelerationsXmlRpc);
237  }
238  else
239  {
240  ROS_ERROR("Parameter max_accelerations not set, shutting down node...");
241  n_.shutdown();
242  }
243 
245  MaxAccelerations.resize(MaxAccelerationsXmlRpc.size());
246  for (int i = 0; i < MaxAccelerationsXmlRpc.size(); i++)
247  {
248  MaxAccelerations[i] = (double)MaxAccelerationsXmlRpc[i];
249  }
250 
252  if ((int)MaxAccelerations.size() != pc_params_->GetDOF())
253  {
254  ROS_ERROR("Wrong dimensions of parameter max_accelerations, shutting down node...");
255  n_.shutdown();
256  }
257  pc_params_->SetMaxAcc(MaxAccelerations);
258 
260  double Horizon;
261  if (n_private_.hasParam("horizon"))
262  {
263  n_private_.getParam("horizon", Horizon);
264  }
265  else
266  {
268  Horizon = 0.05;
269  ROS_WARN("Parameter horizon not available, setting to default value: %f sec", Horizon);
270  }
271  pc_ctrl_->setHorizon(Horizon);
272  }
273 
278  {
279  unsigned int DOF = pc_params_->GetDOF();
280  std::vector<std::string> JointNames = pc_params_->GetJointNames();
281 
283  std::string xml_string;
284  if (n_.hasParam("/robot_description"))
285  {
286  n_.getParam("/robot_description", xml_string);
287  }
288  else
289  {
290  ROS_ERROR("Parameter '/robot_description' not set, shutting down node...");
291  n_.shutdown();
292  }
293 
294  if (xml_string.size() == 0)
295  {
296  ROS_ERROR("Unable to load robot model from parameter /robot_description'");
297  n_.shutdown();
298  }
299 
301  urdf::Model model;
302  if (!model.initString(xml_string))
303  {
304  ROS_ERROR("Failed to parse urdf file");
305  n_.shutdown();
306  }
307  ROS_DEBUG("Successfully parsed urdf file");
308 
310  std::vector<double> MaxVelocities(DOF);
311  for (unsigned int i = 0; i < DOF; i++)
312  {
313  MaxVelocities[i] = model.getJoint(JointNames[i].c_str())->limits->velocity;
314  }
315 
317  std::vector<double> LowerLimits(DOF);
318  for (unsigned int i = 0; i < DOF; i++)
319  {
320  LowerLimits[i] = model.getJoint(JointNames[i].c_str())->limits->lower;
321  }
322 
323  // Get upper limits out of urdf model
324  std::vector<double> UpperLimits(DOF);
325  for (unsigned int i = 0; i < DOF; i++)
326  {
327  UpperLimits[i] = model.getJoint(JointNames[i].c_str())->limits->upper;
328  }
329 
331  std::vector<double> Offsets(DOF);
332  for (unsigned int i = 0; i < DOF; i++)
333  {
334  if(model.getJoint(JointNames[i].c_str())->calibration == NULL)
335  Offsets[i] = 0.0;
336  else
337  Offsets[i] = model.getJoint(JointNames[i].c_str())->calibration->rising.get()[0];
338  }
339 
341  pc_params_->SetMaxVel(MaxVelocities);
342  pc_params_->SetLowerLimits(LowerLimits);
343  pc_params_->SetUpperLimits(UpperLimits);
344  pc_params_->SetOffsets(Offsets);
345  }
346 
353  void topicCallback_CommandPos(const std_msgs::Float64MultiArray::ConstPtr& msg)
354  {
355  ROS_DEBUG("Received new position command");
356  if (!initialized_)
357  {
358  ROS_WARN("Skipping command: powercubes not initialized");
359  publishState();
360  return;
361  }
362 
363  if (pc_ctrl_->getPC_Status() != PowerCubeCtrl::PC_CTRL_OK)
364  {
365  publishState();
366  return;
367  }
368 
370  std::vector<std::string> errorMessages;
371  pc_ctrl_->getStatus(status, errorMessages);
372 
374  if (msg->data.size() != pc_params_->GetDOF())
375  {
376  ROS_ERROR("Skipping command: Commanded positionss and DOF are not same dimension.");
377  return;
378  }
379 
381  if (!pc_ctrl_->MoveJointSpaceSync(msg->data))
382  {
383  error_ = true;
384  error_msg_ = pc_ctrl_->getErrorMessage();
385  ROS_ERROR("Skipping command: %s", pc_ctrl_->getErrorMessage().c_str());
386  return;
387  }
388 
389  ROS_DEBUG("Executed position command");
390 
391  publishState();
392  }
393 
400  void topicCallback_CommandVel(const std_msgs::Float64MultiArray::ConstPtr &msg)
401  {
402  ROS_DEBUG("Received new velocity command");
403  if (!initialized_)
404  {
405  ROS_WARN("Skipping command: powercubes not initialized");
406  publishState(false);
407  return;
408  }
409 
410  if (pc_ctrl_->getPC_Status() != PowerCubeCtrl::PC_CTRL_OK)
411  {
412  publishState(false);
413  return;
414  }
415 
417  std::vector<std::string> errorMessages;
418  pc_ctrl_->getStatus(status, errorMessages);
419 
420  unsigned int DOF = pc_params_->GetDOF();
421 
423  if (msg->data.size() != DOF)
424  {
425  ROS_ERROR("Skipping command: Commanded velocities and DOF are not same dimension.");
426  return;
427  }
428 
430  if (!pc_ctrl_->MoveVel(msg->data))
431  {
432  error_ = true;
433  error_msg_ = pc_ctrl_->getErrorMessage();
434  ROS_ERROR("Skipping command: %s", pc_ctrl_->getErrorMessage().c_str());
435  return;
436  }
437 
438  ROS_DEBUG("Executed velocity command");
439 
440  publishState(false);
441  }
442 
450  bool srvCallback_Init(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
451  {
452  if (!initialized_)
453  {
454  ROS_INFO("Initializing powercubes...");
455 
457  if (pc_ctrl_->Init(pc_params_))
458  {
459  initialized_ = true;
460  res.success = true;
461  ROS_INFO("...initializing powercubes successful");
462  }
463 
464  else
465  {
466  error_ = true;
467  error_msg_ = pc_ctrl_->getErrorMessage();
468  res.success = false;
469  res.message = pc_ctrl_->getErrorMessage();
470  ROS_INFO("...initializing powercubes not successful. error: %s", res.message.c_str());
471  }
472  }
473 
474  else
475  {
476  res.success = true;
477  res.message = "powercubes already initialized";
478  ROS_WARN("...initializing powercubes not successful. error: %s", res.message.c_str());
479  }
480 
481  return true;
482  }
483 
491  bool srvCallback_Stop(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
492  {
493  ROS_INFO("Stopping powercubes...");
494 
496  if (pc_ctrl_->Stop())
497  {
498  res.success = true;
499  ROS_INFO("...stopping powercubes successful.");
500  }
501 
502  else
503  {
504  res.success = false;
505  res.message = pc_ctrl_->getErrorMessage();
506  ROS_ERROR("...stopping powercubes not successful. error: %s", res.message.c_str());
507  }
508  return true;
509  }
510 
518  bool srvCallback_Recover(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
519  {
520  ROS_INFO("Recovering powercubes...");
521  if (initialized_)
522  {
524  if (pc_ctrl_->Recover())
525  {
526  error_ = false;
527  error_msg_ = "";
528  res.success = true;
529  ROS_INFO("...recovering powercubes successful.");
530  }
531  else
532  {
533  res.success = false;
534  error_ = true;
535  error_msg_ = pc_ctrl_->getErrorMessage();
536  res.message = pc_ctrl_->getErrorMessage();
537  ROS_ERROR("...recovering powercubes not successful. error: %s", res.message.c_str());
538  }
539  }
540  else
541  {
542  res.success = false;
543  res.message = "powercubes not initialized";
544  ROS_ERROR("...recovering powercubes not successful. error: %s", res.message.c_str());
545  }
546 
547  return true;
548  }
549 
557  bool srvCallback_SetOperationMode(cob_srvs::SetString::Request &req, cob_srvs::SetString::Response &res)
558  {
559  if (req.data != "velocity")
560  {
561  ROS_WARN("Powercube chain currently only supports velocity commands");
562  res.success = false;
563  }
564  else
565  {
566  res.success = true;
567  }
568  return true;
569  }
570 
577  void publishState(bool update = true)
578  {
579  if (initialized_)
580  {
581  ROS_DEBUG("publish state");
582 
583  if (update)
584  {
585  pc_ctrl_->updateStates();
586  }
587 
588  sensor_msgs::JointState joint_state_msg;
589  joint_state_msg.header.stamp = ros::Time::now();
590  joint_state_msg.name = pc_params_->GetJointNames();
591  joint_state_msg.position = pc_ctrl_->getPositions();
592  joint_state_msg.velocity = pc_ctrl_->getVelocities();
593  joint_state_msg.effort.resize(pc_params_->GetDOF());
594 
595  control_msgs::JointTrajectoryControllerState controller_state_msg;
596  controller_state_msg.header.stamp = joint_state_msg.header.stamp;
597  controller_state_msg.joint_names = pc_params_->GetJointNames();
598  controller_state_msg.actual.positions = pc_ctrl_->getPositions();
599  controller_state_msg.actual.velocities = pc_ctrl_->getVelocities();
600  controller_state_msg.actual.accelerations = pc_ctrl_->getAccelerations();
601 
602  std_msgs::String opmode_msg;
603  opmode_msg.data = "velocity";
604 
606  topicPub_JointState_.publish(joint_state_msg);
607  topicPub_ControllerState_.publish(controller_state_msg);
608  topicPub_OperationMode_.publish(opmode_msg);
609 
610  last_publish_time_ = joint_state_msg.header.stamp;
611  }
612 
613  // check status of PowerCube chain
614  if (pc_ctrl_->getPC_Status() != PowerCubeCtrl::PC_CTRL_OK)
615  {
616  error_ = true;
617  }
618 
619  // check status of PowerCube chain
620  if (pc_ctrl_->getPC_Status() != PowerCubeCtrl::PC_CTRL_OK)
621  {
622  error_ = true;
623  }
624  else
625  {
626  error_ = false;
627  }
628 
629  // publishing diagnotic messages
630  diagnostic_msgs::DiagnosticArray diagnostics;
631  diagnostics.status.resize(1);
632 
633  // set data to diagnostics
634  if (error_)
635  {
636  diagnostics.status[0].level = 2;
637  diagnostics.status[0].name = n_.getNamespace();
638  diagnostics.status[0].message = pc_ctrl_->getErrorMessage();
639  }
640  else
641  {
642  if (initialized_)
643  {
644  diagnostics.status[0].level = 0;
645  diagnostics.status[0].name = n_.getNamespace(); //"schunk_powercube_chain";
646  diagnostics.status[0].message = "powercubechain initialized and running";
647  }
648  else
649  {
650  diagnostics.status[0].level = 1;
651  diagnostics.status[0].name = n_.getNamespace(); //"schunk_powercube_chain";
652  diagnostics.status[0].message = "powercubechain not initialized";
653  }
654  }
655  // publish diagnostic message
656  topicPub_Diagnostic_.publish(diagnostics);
657  }
658 }; // PowerCubeChainNode
659 
665 int main(int argc, char **argv)
666 {
668  ros::init(argc, argv, "powercube_chain");
669 
670  // create PowerCubeChainNode
671  PowerCubeChainNode pc_node;
672  pc_node.getROSParameters();
674 
676  double frequency;
677  if (pc_node.n_private_.hasParam("frequency"))
678  {
679  pc_node.n_private_.getParam("frequency", frequency);
680  // frequency of driver has to be much higher then controller frequency
681  }
682  else
683  {
684  // frequency of driver has to be much higher then controller frequency
685  frequency = 10; // Hz
686  ROS_WARN("Parameter 'frequency' not available, setting to default value: %f Hz", frequency);
687  }
688 
689  ros::Duration min_publish_duration;
690  if (pc_node.n_private_.hasParam("min_publish_duration"))
691  {
692  double sec;
693  pc_node.n_private_.getParam("min_publish_duration", sec);
694  min_publish_duration.fromSec(sec);
695  }
696  else
697  {
698  ROS_ERROR("Parameter 'min_publish_time' not available");
699  return 0;
700  }
701 
702  if ((1.0 / min_publish_duration.toSec()) > frequency)
703  {
704  ROS_ERROR("min_publish_duration has to be longer then delta_t of controller frequency!");
705  return 0;
706  }
707 
709  ros::Rate loop_rate(frequency); // Hz
710  while (pc_node.n_.ok())
711  {
712  if ((ros::Time::now() - pc_node.last_publish_time_) >= min_publish_duration)
713  {
714  pc_node.publishState();
715  }
716 
718  ros::spinOnce();
719  loop_rate.sleep();
720  }
721 
722  return 0;
723 }
724 
725 
bool setHorizon(double horizon)
Sets the horizon (sec).
std::vector< double > getPositions()
Gets the current positions.
std::vector< std::string > GetJointNames()
Gets the joint names.
bool srvCallback_Recover(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Executes the service callback for recover.
void publish(const boost::shared_ptr< M > &message) const
URDF_EXPORT bool initString(const std::string &xmlstring)
Implementation of ROS node for powercube_chain.
int SetLowerLimits(std::vector< double > LowerLimits)
Sets the lower angular limits (rad) for the joints.
ros::ServiceServer srvServer_Recover_
PowerCubeChainNode()
Constructor.
int main(int argc, char **argv)
Main loop of ROS node.
PowerCubeCtrl * pc_ctrl_
handle for powercube_chain
bool MoveVel(const std::vector< double > &velocities)
Moves all cubes by the given velocities.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void getRobotDescriptionParameters()
Gets parameters from the robot_description and configures the powercube_chain.
void getROSParameters()
Gets parameters from the ROS parameter server and configures the powercube_chain. ...
int size() const
PowerCubeCtrlParams * pc_params_
handle for powercube_chain parameters
bool getStatus(PC_CTRL_STATUS &status, std::vector< std::string > &errorMessages)
Gets the status of the modules.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int SetOffsets(std::vector< double > AngleOffsets)
Sets the offset angulars (rad) for the joints.
ros::Subscriber topicSub_CommandVel_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros::Publisher topicPub_JointState_
declaration of topics to publish
void SetUseMoveVel(bool UseMoveVel)
Sets UseMoveVel.
#define ROS_WARN(...)
ros::ServiceServer srvServer_Stop_
ros::Publisher topicPub_Diagnostic_
int SetJointNames(std::vector< std::string > JointNames)
Sets the joint names.
bool Init(PowerCubeCtrlParams *params)
Initializing.
bool Recover()
Recovery after emergency stop or power supply failure.
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
void publishState(bool update=true)
Publishes the state of the powercube_chain as ros messages.
std::vector< double > getAccelerations()
Gets the current accelerations.
bool srvCallback_SetOperationMode(cob_srvs::SetString::Request &req, cob_srvs::SetString::Response &res)
Executes the service callback for SetOperationMode.
std::vector< double > getVelocities()
Gets the current velcities.
Duration & fromSec(double t)
PC_CTRL_STATUS getPC_Status() const
Get PC_Status message.
Definition: PowerCubeCtrl.h:82
void topicCallback_CommandPos(const std_msgs::Float64MultiArray::ConstPtr &msg)
Executes the callback from the command_pos topic.
int SetUpperLimits(std::vector< double > UpperLimits)
Sets the upper angular limits (rad) for the joints.
#define ROS_INFO(...)
bool initialized_
member variables
const std::string & getNamespace() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int GetDOF()
Gets the DOF value.
ros::Publisher topicPub_OperationMode_
int SetMaxAcc(std::vector< double > MaxAcc)
Sets the max. angular accelerations (rad/s^2) for the joints.
bool sleep()
bool srvCallback_Init(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Executes the service callback for init.
ros::ServiceServer srvServer_SetOperationMode_
ros::NodeHandle n_
create a handle for this node, initialize node
bool updateStates()
Returns the state of all modules.
bool Close()
Close.
int SetMaxVel(std::vector< double > MaxVel)
Sets the max. angular velocities (rad/s) for the joints.
ros::ServiceServer srvServer_Init_
declaration of service servers
ros::Subscriber topicSub_CommandPos_
declaration of topics to subscribe, callback is called for new messages arriving
bool getParam(const std::string &key, std::string &s) const
int Init(std::string CanModule, std::string CanDevice, int Baudrate, std::vector< int > ModuleIDs)
Initializing.
bool srvCallback_Stop(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Executes the service callback for stop.
static Time now()
std::string getErrorMessage() const
Get error message.
Definition: PowerCubeCtrl.h:74
void topicCallback_CommandVel(const std_msgs::Float64MultiArray::ConstPtr &msg)
Executes the callback from the command_vel topic.
bool ok() const
bool Stop()
Stops the Manipulator immediately.
bool hasParam(const std::string &key) const
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
Parameters for cob_powercube_chain.
bool MoveJointSpaceSync(const std::vector< double > &angles)
Send position goals to powercubes, the final angles will be reached simultaneously.
ros::Publisher topicPub_ControllerState_
#define ROS_DEBUG(...)


schunk_powercube_chain
Author(s): Florian Weisshardt
autogenerated on Mon Nov 25 2019 03:48:21