pacmod_game_control_node.cpp
Go to the documentation of this file.
1 /*
2 * Unpublished Copyright (c) 2009-2018 AutonomouStuff, LLC, All Rights Reserved.
3 *
4 * This file is part of the PACMod ROS 1.0 driver which is released under the MIT license.
5 * See file LICENSE included with this software or go to https://opensource.org/licenses/MIT for full license details.
6 */
7 
9 #include "globals.h"
10 #include "startup_checks.h"
11 
12 using namespace AS::Joystick;
13 
14 /*
15  * Main method running the ROS Node
16  */
17 int main(int argc, char *argv[])
18 {
19  ros::init(argc, argv, "pacmod_gamepad_control");
20  ros::AsyncSpinner spinner(2);
21  ros::NodeHandle priv("~");
22 
23  // Wait for time to be valid
24  while (ros::Time::now().nsec == 0);
25 
26  if(run_startup_checks_error(&priv) == true)
27  return 0;
28 
29  // Check ROS params for board type
30  int board_rev = 1;
31  priv.getParam("pacmod_board_rev", board_rev);
32 
33  // Create an instance of the appropriate board type
34  std::unique_ptr<PublishControl> board;
35 
36  try
37  {
38  board = PublishControlFactory::create(board_rev);
39  }
40  catch (const std::invalid_argument& ia)
41  {
42  ROS_ERROR("Invalid PACMod Board Version received. Board requested was %d", board_rev);
43  return 0;
44  }
45 
46  spinner.start();
48 
49  return 0;
50 }
51 
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool run_startup_checks_error(ros::NodeHandle *nodeH)
int main(int argc, char *argv[])
static std::unique_ptr< PublishControl > create(int board_rev)
bool getParam(const std::string &key, std::string &s) const
static Time now()
#define ROS_ERROR(...)
ROSCPP_DECL void waitForShutdown()


pacmod_game_control
Author(s): Joe Driscoll
autogenerated on Thu Jun 6 2019 19:19:40