/** * Create an Erlang port from its components. * If node string size is greater than MAX_NODE_LENGTH or = 0, * the constructor throws an exception. * @param node the nodename. * @param id an arbitrary number. Only the low order 18 * bits will be used. * @param creation yet another arbitrary number. Only the low order * 2 bits will be used. * @throw err_bad_argument if node is empty or greater than MAX_NODE_LENGTH **/ port(const char* node, const int id, const int creation, const Alloc& a_alloc = Alloc()) throw (err_bad_argument) { size_t n = strlen(node); detail::check_node_length(n); atom l_node(node, n); init(l_node, id, creation, a_alloc); }
int main ( int argc, char** argv ) { ros::init(argc, argv, "Agent_motor_control"); std::string l_robot_name; ros::NodeHandle l_node("~"); l_node.getParam("robot_name", l_robot_name); Robotics::GameTheory::Motor_control comm(l_robot_name); ros::spin(); return 0; }
int main(int argc, char **argv) { ros::init(argc, argv, "Simulator"); ROS_INFO("Simulator is running."); std::shared_ptr<GazeboDriver> l_gazebo_driver = std::make_shared<GazeboDriver>(); ROS_INFO("Gazebo Driver is created."); int l_number_of_guards(0), l_number_of_thieves(0); std::string l_str; ros::NodeHandle l_node("~"); std::string temp_name; if (l_node.searchParam("number_of_guards", temp_name)) { l_node.getParam(temp_name,l_number_of_guards); //l_number_of_guards = std::stoi(l_str); ROS_INFO("Received number of guards: %d", l_number_of_guards); } else { l_number_of_guards = 1; ROS_ERROR("Apriori number of guards: %d", l_number_of_guards); } if (l_node.searchParam("number_of_thieves", temp_name)) { l_node.getParam(temp_name,l_number_of_thieves); //l_number_of_thieves = std::stoi(l_str); ROS_INFO("Received number of thieves: %d", l_number_of_thieves); } else { l_number_of_thieves = 1; ROS_ERROR("Apriori number of thieves: %d", l_number_of_thieves); } ///////////////////////////////////////////////// // AREA CREATOR Robotics::GameTheory::AreaPtr l_area = nullptr; ros::NodeHandle l_nodeArea; ros::ServiceClient l_clientArea = l_nodeArea.serviceClient<nostop_area::AreaData>("/AreaInitializer"); nostop_area::AreaData l_srvArea; if (l_clientArea.call(l_srvArea)) { ROS_INFO("Area description received"); // creazione dell'area: Robotics::GameTheory::AreaCreator l_areaCreator(l_srvArea.response.external, l_srvArea.response.internal); l_area = l_areaCreator.getArea(); } else { ROS_ERROR("Failed to call service AreaInitializer"); Robotics::GameTheory::AreaCreator l_areaCreator; l_area = l_areaCreator.getArea(); } ROS_INFO("Area is created."); ///////////////////////////////////////////////// // PLAYER CREATOR Robotics::GameTheory::PlayersMaker l_playersCreator(l_area, l_number_of_guards, l_number_of_thieves, l_gazebo_driver); std::set<Robotics::GameTheory::AgentPtr> l_players = l_playersCreator.getPlayers(); ROS_INFO("Players are connected."); ///////////////////////////////////////////////// // LEARNING CREATOR std::shared_ptr<Robotics::GameTheory::LearningWorld> l_coverage = std::make_shared<Robotics::GameTheory::LearningWorld>(l_players, l_area->discretize(), Robotics::GameTheory::DISL); ROS_INFO("Learning algorithm is created."); ///////////////////////////////////////////////// // APPLICATION RUNNING Robotics::GameTheory::CoverageApplication l_application(l_coverage); l_application.start(); ROS_INFO("Application is running."); // std::shared_ptr<Robotics::GameTheory::PlayerAdder> l_player_adder = std::make_shared<Robotics::GameTheory::PlayerAdder>(l_coverage, l_gazebo_driver); // std::shared_ptr<Robotics::GameTheory::PlayerRemover> l_player_remover = std::make_shared<Robotics::GameTheory::PlayerRemover>(l_coverage, l_gazebo_driver); // l_player_adder->start(); // l_player_remover->start(); ///////////////////////////////////////////////// // WAIT FOR ROS MESSAGES ros::spin(); ROS_INFO("Ending process."); return 0; }