diff --git a/Makefile.am b/Makefile.am index 9dc8439c9c30db1570f879b57bdea86d30b90d12..80cd3745613ec35f5c130f542cf4bb7de078c7bc 100644 --- a/Makefile.am +++ b/Makefile.am @@ -1,4 +1,4 @@ -SUBDIRS = mpidep rudeconfig src utils @TESTDIR@ @EXTRAS@ doc @EXAMPLESDIR@ @MUSICCONFIGDIR@ @PYMUSIC_SUBDIR@ +SUBDIRS = mpidep rudeconfig src utils @TESTDIR@ @EXTRAS@ doc @EXAMPLESDIR@ @MUSICCONFIGDIR@ @PYMUSIC_SUBDIR@ @ROS_SUBDIR@ debdir=../@PACKAGE_NAME@-@PACKAGE_VERSION@ diff --git a/configure.ac b/configure.ac index 803b2de36968ee28a4280973f7a5cb71c944bfb2..6a8e7300928ee27bfa2ea0b701c5fd5116a117b8 100644 --- a/configure.ac +++ b/configure.ac @@ -345,9 +345,24 @@ fi fi +AC_MSG_CHECKING([whether to build ROS Toolchain]) +AC_ARG_WITH([ros]) +ROS_SUBDIR="" +AS_IF([test "x$with_ros" = "xyes"], [ROS_SUBDIR="ros"], [with_ros=no]) +AC_MSG_RESULT([$with_ros]) + +# if ROS is to be compiled +if test "x$with_ros" = "xyes" ; then + AC_CONFIG_FILES(ros/Makefile) + AC_CONFIG_FILES(ros/adapters/Makefile) + AC_CONFIG_FILES(ros/encoder/Makefile) + AC_CONFIG_FILES(ros/decoder/Makefile) +fi + AC_SUBST([HAVE_PYTHON]) AC_SUBST([MUSICCONFIGDIR]) AC_SUBST([PYMUSIC_SUBDIR]) +AC_SUBST([ROS_SUBDIR]) AC_SUBST([PYEXECDIR], ${pyexecdir}) AC_SUBST([PYTHON]) diff --git a/ros/Makefile.am b/ros/Makefile.am new file mode 100644 index 0000000000000000000000000000000000000000..571c168ed332924da4b603e6673baf9702496550 --- /dev/null +++ b/ros/Makefile.am @@ -0,0 +1,3 @@ +SUBDIRS = adapters encoder decoder + + diff --git a/ros/README.md b/ros/README.md new file mode 100644 index 0000000000000000000000000000000000000000..eb1dbd64bf9c761ced4ac0eb225d3f2f072826c9 --- /dev/null +++ b/ros/README.md @@ -0,0 +1,21 @@ +# ros_music_adapter + +## Software Dependencies +- MUSIC (https://github.com/INCF/MUSIC) +- ROS (http://wiki.ros.org/ROS/Installation) +- CMake +- OpenMPI +- GSL BLAS +- Json-cpp +- pthread + +##### Additional Software +- Gazebo (http://gazebosim.org/) +- NEST (http://nest-simulator.org/) +- NEURON (http://neuron.yale.edu/neuron/) + +## Installation +- cmake . +- make + + diff --git a/ros/adapters/Makefile.am b/ros/adapters/Makefile.am new file mode 100644 index 0000000000000000000000000000000000000000..4e3817e1be22666bd32f8cf9d7c63e5bc7d88046 --- /dev/null +++ b/ros/adapters/Makefile.am @@ -0,0 +1,28 @@ +bin_PROGRAMS = connect_adapter ros_sensor_adapter ros_command_adapter + + +# look for ros in the common paths +LD_ROS_PATH = -L/opt/ros/kinetic/lib/ \ + -L/opt/ros/jade/lib/ + +INC_ROS_PATH = -I/opt/ros/kinetic/include \ + -I/opt/ros/jade/include + +AM_CXXFLAGS = $(INC_ROS_PATH) -I$(top_srcdir) -I$(top_srcdir)/src -I$(top_builddir)/src @MPI_CXXFLAGS@ +AM_LDFLAGS = $(top_builddir)/mpidep/libmpidep.la @MPI_LDFLAGS@ \ + $(top_builddir)/src/libmusic.la \ + $(top_builddir)/src/libmusic-c.la \ + $(LD_ROS_PATH) + + +connect_adapter_SOURCES = connect.h connect.cpp +connect_adapter_LDADD = -lgsl -lgslcblas -ljsoncpp + +ros_sensor_adapter_SOURCES = ros_sensor_adapter.h ros_sensor_adapter.cpp rtclock.h rtclock.cpp +ros_sensor_adapter_LDADD = -lroscpp -lrosconsole -lrostime -lroscpp_serialization -lgsl -lgslcblas + +ros_command_adapter_SOURCES = ros_command_adapter.h ros_command_adapter.cpp rtclock.h rtclock.cpp +ros_command_adapter_LDADD = -lroscpp -lrosconsole -lrostime -lroscpp_serialization -lgsl -lgslcblas -ljsoncpp + + + diff --git a/ros/adapters/connect.cpp b/ros/adapters/connect.cpp new file mode 100644 index 0000000000000000000000000000000000000000..d9c75e7628669b7c3239a982ba65b71ac47fa1cf --- /dev/null +++ b/ros/adapters/connect.cpp @@ -0,0 +1,197 @@ +/* + * This file is part of MUSIC. + * Copyright (C) 2016 INCF + * + * MUSIC is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * MUSIC is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see <http://www.gnu.org/licenses/>. + */ + +#include "connect.h" + +int +main(int argc, char** argv) +{ + + ConnectAdapter conn_adapter; + conn_adapter.init(argc, argv); + conn_adapter.runMUSIC(); + conn_adapter.finalize(); + +} + +void +ConnectAdapter::init(int argc, char** argv) +{ + std::cout << "initializing connect adapter" << std::endl; + timestep = DEFAULT_TIMESTEP; + weights_filename = DEFAULT_WEIGHTS_FILENAME; + initMUSIC(argc, argv); + readWeightsFile(); +} + +void +ConnectAdapter::initMUSIC(int argc, char** argv) +{ + MUSIC::Setup* setup = new MUSIC::Setup (argc, argv); + + setup->config("stoptime", &stoptime); + setup->config("music_timestep", ×tep); + setup->config("weights_filename", &weights_filename); + + port_in = setup->publishContInput("in"); + port_out = setup->publishContOutput("out"); + + comm = setup->communicator (); + int rank = comm.Get_rank (); + int nProcesses = comm.Get_size (); + if (nProcesses > 1) + { + std::cout << "ERROR: num processes (np) not equal 1" << std::endl; + comm.Abort(1); + } + + // get dimensions of data + if (port_in->hasWidth() && port_out->hasWidth()) + { + size_data_in = port_in->width(); + size_data_out = port_out->width(); + } + else + { + std::cout << "ERROR: Port-width not defined" << std::endl; + comm.Abort(1); + } + + data_in = new double[size_data_in]; + for (int i = 0; i < size_data_in; ++i) + { + data_in[i] = 0.; + } + vec_data_in = gsl_vector_view_array(data_in, size_data_in); + + data_out = new double[size_data_out]; + for (int i = 0; i < size_data_out; ++i) + { + data_out[i] = 0.; + } + vec_data_out = gsl_vector_view_array(data_out, size_data_out); + + weights = new double[size_data_out * size_data_in]; + for (int i = 0; i < size_data_out * size_data_in; ++i) + { + weights[i] = 0.; + } + mat_weights = gsl_matrix_view_array(weights, size_data_out, size_data_in); + + // Declare where in memory to put command_data + MUSIC::ArrayData dmap_in(data_in, + MPI::DOUBLE, + 0, + size_data_in); + port_in->map (&dmap_in, 0., 1, false); + + MUSIC::ArrayData dmap_out(data_out, + MPI::DOUBLE, + 0, + size_data_out); + port_out ->map (&dmap_out, 1); + + MPI::COMM_WORLD.Barrier(); + runtime = new MUSIC::Runtime (setup, timestep); +} + +void +ConnectAdapter::readWeightsFile() +{ + Json::Reader json_reader; + + std::ifstream weights_file; + weights_file.open(weights_filename.c_str(), std::ios::in); + string json_weights_ = ""; + string line; + + while (std::getline(weights_file, line)) + { + json_weights_ += line; + } + weights_file.close(); + + if ( !json_reader.parse(json_weights_, json_weights)) + { + // report to the user the failure and their locations in the document. + std::cout << "WARNING: linear readout: Failed to parse file \"" << weights_filename << "\"\n" + << json_weights_ << " It has to be in JSON format.\n Using 1/N for each weight." + << json_reader.getFormattedErrorMessages(); + + for (int i = 0; i < size_data_out * size_data_in; ++i) + { + weights[i] = 1. / size_data_in; + } + + return; + } + else + { + for (int i = 0; i < size_data_out; ++i) + { + for (int j = 0; j < size_data_in; ++j) + { + weights[i*size_data_in + j] = json_weights[i][j].asDouble(); + } + } + + } + +} + +void +ConnectAdapter::runMUSIC() +{ + std::cout << "running connect adapter" << std::endl; + + struct timeval start; + struct timeval end; + gettimeofday(&start, NULL); + unsigned int ticks_skipped = 0; + + for (int t = 0; runtime->time() < stoptime; t++) + { + + gsl_blas_dgemv(CblasNoTrans, 1., &mat_weights.matrix, &vec_data_in.vector, 0., &vec_data_out.vector); + +#if DEBUG_OUTPUT + std::cout << "Connect Adapter: "; + for (int i = 0; i < size_data_out; ++i) + { + std::cout << data_out[i] << " "; + } + std::cout << std::endl; +#endif + runtime->tick(); + } + + gettimeofday(&end, NULL); + unsigned int dt_s = end.tv_sec - start.tv_sec; + unsigned int dt_us = end.tv_usec - start.tv_usec; + if (end.tv_sec > start.tv_sec) + { + dt_us += 1000000; + } + std::cout << "connect adapter: total simtime: " << dt_s << " " << dt_us << " ticks skipped " << ticks_skipped << std::endl; +} + +void +ConnectAdapter::finalize(){ + runtime->finalize(); + delete runtime; +} diff --git a/ros/adapters/connect.h b/ros/adapters/connect.h new file mode 100644 index 0000000000000000000000000000000000000000..d90df7a098cf45a4fe88ef32dc85a79b3edc97d4 --- /dev/null +++ b/ros/adapters/connect.h @@ -0,0 +1,69 @@ +/* -*- C++ -*- + * This file is part of MUSIC. + * Copyright (C) 2016 INCF + * + * MUSIC is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * MUSIC is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see <http://www.gnu.org/licenses/>. + */ + +#include <music.hh> +#include <mpi.h> + +#include <vector> +#include <cmath> +#include <unistd.h> +#include "sys/time.h" +#include "jsoncpp/json/json.h" +#include <iostream> +#include <fstream> + +#include <gsl/gsl_matrix_double.h> +#include <gsl/gsl_vector_double.h> +#include <gsl/gsl_blas.h> + +#define DEBUG_OUTPUT false + +const double DEFAULT_TIMESTEP = 1e-3; +const string DEFAULT_WEIGHTS_FILENAME = "connection_weights.dat"; + +class ConnectAdapter{ +public: + void init(int argc, char** argv); + void runMUSIC(); + void finalize(); + +private: + MPI::Intracomm comm; + MUSIC::Runtime* runtime; + double stoptime; + double timestep; + int size_data_in; + int size_data_out; + double* data_in; + gsl_vector_view vec_data_in; + double* data_out; + gsl_vector_view vec_data_out; + + string weights_filename; + Json::Value json_weights; + double* weights; + gsl_matrix_view mat_weights; + + MUSIC::ContInputPort* port_in; + MUSIC::ContOutputPort* port_out; + + void initMUSIC(int argc, char** argv); + void readWeightsFile(); +}; + + diff --git a/ros/adapters/ros_command_adapter.cpp b/ros/adapters/ros_command_adapter.cpp new file mode 100644 index 0000000000000000000000000000000000000000..d0b5782611ef1d75be0b711cc356e920e816d490 --- /dev/null +++ b/ros/adapters/ros_command_adapter.cpp @@ -0,0 +1,359 @@ +/* + * This file is part of MUSIC. + * Copyright (C) 2016 INCF + * + * MUSIC is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * MUSIC is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see <http://www.gnu.org/licenses/>. + */ + +#include "ros_command_adapter.h" + +#include "rtclock.h" + +static void* +ros_thread(void* arg) +{ + RosCommandAdapter* ros_adapter = static_cast<RosCommandAdapter*>(arg); + ros_adapter->runROS(); +} + +int +main(int argc, char** argv) +{ + + RosCommandAdapter ros_adapter; + ros_adapter.init(argc, argv); + + MPI::COMM_WORLD.Barrier(); + // If sensor_update_rate and timestep match to a relative + // precision of 0.1%, lump the ROS and MUSIC event loops + // together. + if (ros_adapter.ratesMatch (0.001)) + { + ros_adapter.runROSMUSIC(); + } + else + { + pthread_t t; + pthread_create (&t, NULL, ros_thread, &ros_adapter); + + ros_adapter.runMUSIC(); + pthread_join(t, NULL); + } + + ros_adapter.finalize(); + +} + + +bool +RosCommandAdapter::ratesMatch (double precision) +{ + return std::abs (command_rate * timestep - 1.) < precision; +} + + +void +RosCommandAdapter::init(int argc, char** argv) +{ + std::cout << "initializing ROS command adapter" << std::endl; + + timestep = DEFAULT_TIMESTEP; + command_rate = DEFAULT_COMMAND_RATE; + msg_type = DEFAULT_MESSAGE_TYPE; + rtf = DEFAULT_RTF; + + pthread_mutex_init(&data_mutex, NULL); + + // MUSIC before ROS to read the config first! + initMUSIC(argc, argv); + initROS(argc, argv); +} + + +void +RosCommandAdapter::initROS(int argc, char** argv) +{ + ros::init(argc, argv, "ros_command_node"); + ros::start(); + + ros::NodeHandle n; + switch (msg_type) + { + case Float64MultiArray: + { + publisher = n.advertise<std_msgs::Float64MultiArray>(ros_topic, 1); + break; + } + case Twist: + { + publisher = n.advertise<geometry_msgs::Twist>(ros_topic, 1); + break; + } + } +} + +void +RosCommandAdapter::initMUSIC(int argc, char** argv) +{ + setup = new MUSIC::Setup (argc, argv); + + setup->config("ros_topic", &ros_topic); + setup->config("stoptime", &stoptime); + setup->config("command_rate", &command_rate); + setup->config("music_timestep", ×tep); + setup->config("rtf", &rtf); + + setup->config("message_mapping_filename", &mapping_filename); + readMappingFile(); + + MUSIC::ContInputPort* port_in = setup->publishContInput ("in"); //TODO: read portname from file + + comm = setup->communicator (); + int rank = comm.Get_rank (); + int nProcesses = comm.Get_size (); + if (nProcesses > 1) + { + std::cout << "ERROR: num processes (np) not equal 1" << std::endl; + comm.Abort(1); + } + + int width = 0; + if (port_in->hasWidth ()) + { + width = port_in->width (); + } + else + { + std::cout << "ERROR: Port-width not defined" << std::endl; + comm.Abort (1); + } + + datasize = width; + data = new double[datasize+1]; //+1 for the leading zero needed for unspecified fiels in the message + data[0] = 0.; + + // Declare where in memory to put data + MUSIC::ArrayData dmap (&data[1], + MPI::DOUBLE, + 0, + datasize); + port_in->map (&dmap, 0., 1, false); +} + +void +RosCommandAdapter::readMappingFile() +{ + Json::Reader json_reader; + + std::ifstream mapping_file; + mapping_file.open(mapping_filename.c_str(), std::ios::in); + string json_mapping_= ""; + string line; + + while (std::getline(mapping_file, line)) + { + json_mapping_ += line; + } + mapping_file.close(); + + if ( !json_reader.parse(json_mapping_, json_mapping)) + { + // report to the user the failure and their locations in the document. + std::cout << "WARNING: ROS Command Adapter: Failed to parse file \"" << mapping_filename << "\"\n" + << json_mapping_ << " It has to be in JSON format.\n" + << json_reader.getFormattedErrorMessages(); + return; + } + else + { + std::string _msg_type; + _msg_type = json_mapping["message_type"].asString(); + if (_msg_type.compare("Float64MultiArray") == 0) + { + msg_type = Float64MultiArray; + // no mapping needed + } + else if (_msg_type.compare("Twist") == 0) + { + msg_type = Twist; + + msg_map = new int[6]; + int index = -1; + + index = json_mapping["mapping"]["linear.x"].asInt(); + msg_map[0] = index + 1; + + index = -1; + index = json_mapping["mapping"]["linear.y"].asInt(); + msg_map[1] = index + 1; + + index = -1; + index = json_mapping["mapping"]["linear.z"].asInt(); + msg_map[2] = index + 1; + + index = -1; + index = json_mapping["mapping"]["angular.x"].asInt(); + msg_map[3] = index + 1; + + index = -1; + index = json_mapping["mapping"]["angular.y"].asInt(); + msg_map[4] = index + 1; + + index = -1; + index = json_mapping["mapping"]["angular.z"].asInt(); + msg_map[5] = index + 1; + } + else + { + std::cout << "ERROR: msg type unknown" << std::endl; + finalize(); + } + + } + +} + +void +RosCommandAdapter::sendROS () +{ + switch (msg_type) + { + case Float64MultiArray: + { + std_msgs::Float64MultiArray msg; + for (int i = 1; i < datasize+1; ++i) + { + msg.data.push_back(data[i]); + } + publisher.publish(msg); + break; + } + + case Twist: + { + geometry_msgs::Twist msg; + + msg.linear.x = data[msg_map[0]]; + msg.linear.y = data[msg_map[1]]; + msg.linear.z = data[msg_map[2]]; + + msg.angular.x = data[msg_map[3]]; + msg.angular.y = data[msg_map[4]]; + msg.angular.z = data[msg_map[5]]; + + publisher.publish(msg); + break; + } + } +} + +void +RosCommandAdapter::runROSMUSIC() +{ + std::cout << "running command adapter with update rate of " << command_rate << std::endl; + RTClock clock( 1. / (command_rate * rtf)); + + runtime = new MUSIC::Runtime (setup, timestep); + ros::spinOnce(); + + for (int t = 0; runtime->time() < stoptime; t++) + { + sendROS(); + clock.sleepNext(); + runtime->tick(); + ros::spinOnce(); + } + +#if MEASUREMENT_OUTPUT + saveRuntime(clock.time ()); +#endif + + std::cout << "command: total simtime: " << clock.time () << " s" << std::endl; +} + +void +RosCommandAdapter::runROS() +{ + RTClock clock(1. / (command_rate * rtf)); + + // wait until first sensor update arrives + while (ros::Time::now().toSec() == 0.) + { + clock.sleepNext(); + } + + ros::Time stop_time = ros::Time::now() + ros::Duration(stoptime/rtf); + + ros::spinOnce() ; + for (ros::Time t = ros::Time::now(); t < stop_time; t = ros::Time::now()) + { + pthread_mutex_lock (&data_mutex); + sendROS(); + pthread_mutex_unlock (&data_mutex); +#if DEBUG_OUTPUT + std::cout << "ROS Command Adapter: "; + for (int i = 1; i < datasize + 1; ++i) + { + std::cout << data[i] << " "; + } + std::cout << std::endl; +#endif + + clock.sleepNext(); + ros::spinOnce(); + } + +} + +void +RosCommandAdapter::runMUSIC() +{ + std::cout << "running command adapter with update rate of " << command_rate << std::endl; + RTClock clock(timestep / rtf); + + runtime = new MUSIC::Runtime (setup, timestep); + + for (int t = 0; runtime->time() < stoptime; t++) + { + clock.sleepNext(); + pthread_mutex_lock (&data_mutex); + runtime->tick(); + pthread_mutex_unlock (&data_mutex); + } + +#if MEASUREMENT_OUTPUT + saveRuntime(clock.time ()); +#endif + + std::cout << "command: total simtime: " << clock.time () << " s" << std::endl; +} + +void RosCommandAdapter::finalize() +{ + + runtime->finalize(); + delete runtime; +} + +#if MEASUREMENT_OUTPUT +void RosCommandAdapter::saveRuntime(double rt) +{ + std::ofstream data_file; + data_file.open("runtime.dat", std::ios::out); + data_file << rt; + data_file.close(); +} +#endif + + diff --git a/ros/adapters/ros_command_adapter.h b/ros/adapters/ros_command_adapter.h new file mode 100644 index 0000000000000000000000000000000000000000..32e21c747a8f5bd900e291b73dbedf6bbd4e65ec --- /dev/null +++ b/ros/adapters/ros_command_adapter.h @@ -0,0 +1,86 @@ +/* -*- C++ -*- + * This file is part of MUSIC. + * Copyright (C) 2016 INCF + * + * MUSIC is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * MUSIC is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see <http://www.gnu.org/licenses/>. + */ + +#include <iostream> +#include <map> + +#include <ros/ros.h> +#include "geometry_msgs/Twist.h" +#include "std_msgs/Float64MultiArray.h" + +#include <music.hh> +#include <mpi.h> + +#include "sys/time.h" + +#include "jsoncpp/json/json.h" +#include <fstream> +#include <pthread.h> + +#define DEBUG_OUTPUT false +#define MEASUREMENT_OUTPUT false + +enum msg_types {Float64MultiArray, Twist}; + +const double DEFAULT_TIMESTEP = 1e-3; +const double DEFAULT_COMMAND_RATE = 10; +const double DEFAULT_RTF = 1.0; +const msg_types DEFAULT_MESSAGE_TYPE = Float64MultiArray; + +class RosCommandAdapter +{ +public: + void init(int argc, char** argv); + bool ratesMatch (double precision); + void runMUSIC(); + void runROS(); + void runROSMUSIC(); + void finalize(); + +private: + std::string ros_topic; + ros::Publisher publisher; + + MPI::Intracomm comm; + MUSIC::Setup* setup; + MUSIC::Runtime* runtime; + double stoptime; + int datasize; + + pthread_mutex_t data_mutex; + double* data; + + double timestep; + double command_rate; + double rtf; + + string mapping_filename; + Json::Value json_mapping; + msg_types msg_type; + int* msg_map; + + void initROS(int argc, char** argv); + void initMUSIC(int argc, char** argv); + void sendROS(); + + void readMappingFile(); + +#if MEASUREMENT_OUTPUT + void saveRuntime(double rt); +#endif +}; diff --git a/ros/adapters/ros_sensor_adapter.cpp b/ros/adapters/ros_sensor_adapter.cpp new file mode 100644 index 0000000000000000000000000000000000000000..c9931585bb628f69d323553e9da94fc785d073fe --- /dev/null +++ b/ros/adapters/ros_sensor_adapter.cpp @@ -0,0 +1,306 @@ +/* + * This file is part of MUSIC. + * Copyright (C) 2016 INCF + * + * MUSIC is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * MUSIC is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see <http://www.gnu.org/licenses/>. + */ + +#include "ros_sensor_adapter.h" + +#include "rtclock.h" + +static void* +ros_thread(void* arg) +{ + RosSensorAdapter* ros_adapter = static_cast<RosSensorAdapter*>(arg); + ros_adapter->runROS(); +} + +int +main(int argc, char** argv) +{ + + RosSensorAdapter ros_adapter; + ros_adapter.init(argc, argv); + + MPI::COMM_WORLD.Barrier(); + // If sensor_update_rate and timestep match to a relative + // precision of 0.1%, lump the ROS and MUSIC event loops + // together. + if (ros_adapter.ratesMatch (0.001)) + { + ros_adapter.runROSMUSIC(); + } + else + { + pthread_t t; + pthread_create (&t, NULL, ros_thread, &ros_adapter); + + ros_adapter.runMUSIC(); + pthread_join(t, NULL); + } + + ros_adapter.finalize(); + +} + + +bool +RosSensorAdapter::ratesMatch (double precision) +{ + return std::abs (sensor_update_rate * timestep - 1.) < precision; +} + + +void +RosSensorAdapter::init(int argc, char** argv) +{ + std::cout << "initializing ROS sensor adapter" << std::endl; + + timestep = DEFAULT_TIMESTEP; + sensor_update_rate = DEFAULT_SENSOR_UPDATE_RATE; + ros_node_name = DEFAULT_ROS_NODE_NAME; + rtf = DEFAULT_RTF; + + pthread_mutex_init(&data_mutex, NULL); + + // MUSIC before ROS to read the config first! + initMUSIC(argc, argv); + initROS(argc, argv); +} + + +void +RosSensorAdapter::initROS(int argc, char** argv) +{ + ros::init(argc, argv, ros_node_name); + ros::start(); + + ros::NodeHandle n; + switch (msg_type) + { + case Laserscan: + subscriber = n.subscribe(ros_topic, 1000, &RosSensorAdapter::laserscanCallback, this); + break; + case Twist: + subscriber = n.subscribe(ros_topic, 1000, &RosSensorAdapter::twistCallback, this); + break; + case Float64MultiArray: + subscriber = n.subscribe(ros_topic, 1000, &RosSensorAdapter::float64MultiArrayCallback, this); + break; + } +} + +void +RosSensorAdapter::initMUSIC(int argc, char** argv) +{ + setup = new MUSIC::Setup (argc, argv); + + setup->config("ros_topic", &ros_topic); + setup->config("stoptime", &stoptime); + setup->config("sensor_update_rate", &sensor_update_rate); + setup->config("ros_node_name", &ros_node_name); + setup->config("rtf", &rtf); + + std::string _msg_type; + setup->config("message_type", &_msg_type); + + if (_msg_type.compare("Laserscan") == 0){ + msg_type = Laserscan; + } + else if (_msg_type.compare("Twist") == 0){ + msg_type = Twist; + } + else if (_msg_type.compare("FloatArray") == 0){ + msg_type = Float64MultiArray; + } + else + { + std::cout << "ERROR: msg type unknown" << std::endl; + finalize(); + } + + + MUSIC::ContOutputPort* port_out = setup->publishContOutput ("out"); + + comm = setup->communicator (); + int rank = comm.Get_rank (); + int nProcesses = comm.Get_size (); + if (nProcesses > 1) + { + std::cout << "ERROR: num processes (np) not equal 1" << std::endl; + comm.Abort(1); + } + + + if (port_out->hasWidth ()) + { + datasize = port_out->width (); + } + else + { + std::cout << "ERROR: Port-width not defined" << std::endl; + comm.Abort (1); + } + + data = new double[datasize]; + for (unsigned int i = 0; i < datasize; ++i) + { + data[i] = 0.; + } + + // Declare where in memory to put data + MUSIC::ArrayData dmap (data, + MPI::DOUBLE, + 0, + datasize); + port_out->map (&dmap, 1); +} + +void +RosSensorAdapter::runROSMUSIC() +{ + std::cout << "running sensor adapter with update rate of " << sensor_update_rate << std::endl; + RTClock clock( 1. / (sensor_update_rate * rtf) ); + + ros::spinOnce(); + runtime = new MUSIC::Runtime (setup, timestep); + + for (int t = 0; runtime->time() < stoptime; t++) + { + +#if DEBUG_OUTPUT + std::cout << "ROS Sensor Adapter: "; + for (int i = 0; i < datasize; ++i) + { + std::cout << data[i] << " "; + } + std::cout << std::endl; +#endif + + clock.sleepNext(); + ros::spinOnce(); + runtime->tick(); + } + + std::cout << "sensor: total simtime: " << clock.time () << " s" << std::endl; +} + +void +RosSensorAdapter::runROS() +{ + RTClock clock( 1. / (sensor_update_rate * rtf) ); + + // wait until first sensor update arrives + while (ros::Time::now().toSec() == 0.) + { + clock.sleepNext(); + } + + ros::Time stop_time = ros::Time::now() + ros::Duration(stoptime/rtf); + + ros::spinOnce(); + for (ros::Time t = ros::Time::now(); t < stop_time; t = ros::Time::now()) + { +#if DEBUG_OUTPUT + std::cout << "ROS Sensor Adapter: "; + for (int i = 0; i < datasize; ++i) + { + std::cout << data[i] << " "; + } + std::cout << std::endl; +#endif + + clock.sleepNext(); + ros::spinOnce(); + } +} + +void +RosSensorAdapter::runMUSIC() +{ + std::cout << "running sensor adapter with update rate of " << sensor_update_rate << std::endl; + RTClock clock(timestep / rtf); + + runtime = new MUSIC::Runtime (setup, timestep); + + for (int t = 0; runtime->time() < stoptime; t++) + { + clock.sleepNext(); + pthread_mutex_lock(&data_mutex); + runtime->tick(); + pthread_mutex_unlock(&data_mutex); + } + + std::cout << "sensor: total simtime: " << clock.time () << " s" << std::endl; +} + +void +RosSensorAdapter::laserscanCallback(const sensor_msgs::LaserScanConstPtr& msg) +{ + pthread_mutex_lock(&data_mutex); + for (unsigned int i = 0; i < msg->ranges.size(); ++i) + { + // scale data between -1 and 1 + // TODO: catch exception if ranges.size not width of port + if (isinf(msg->ranges.at(i))){ + data[i] = 1.; + } + else{ + data[i] = ((msg->ranges.at(i) - msg->range_min) / (msg->range_max - msg->range_min) ) * 2 - 1; + } + } + pthread_mutex_unlock(&data_mutex); +} + +void +RosSensorAdapter::twistCallback(const geometry_msgs::Twist msg) +{ + pthread_mutex_lock(&data_mutex); + + data[0] = msg.linear.x; + data[1] = msg.angular.z; + for (unsigned int i = 0; i < 2; ++i) // Twist msg has 2 dimensions + { + // limit data between -1 and 1 + if (data[i] > 1) + data[i] = 1; + else if (data[i] < -1) + data[i] = -1; + + } + + pthread_mutex_unlock(&data_mutex); +} + +void +RosSensorAdapter::float64MultiArrayCallback(const std_msgs::Float64MultiArray msg) +{ + pthread_mutex_lock(&data_mutex); + + for (unsigned int i = 0; i < datasize; ++i) + { + data[i] = msg.data[i]; + } + + pthread_mutex_unlock(&data_mutex); +} + +void RosSensorAdapter::finalize(){ + runtime->finalize(); + delete runtime; +} + + + diff --git a/ros/adapters/ros_sensor_adapter.h b/ros/adapters/ros_sensor_adapter.h new file mode 100644 index 0000000000000000000000000000000000000000..6d06094283112886949421760c58545d83764c44 --- /dev/null +++ b/ros/adapters/ros_sensor_adapter.h @@ -0,0 +1,80 @@ +/* -*- C++ -*- + * This file is part of MUSIC. + * Copyright (C) 2016 INCF + * + * MUSIC is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * MUSIC is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see <http://www.gnu.org/licenses/>. + */ + +#include <iostream> +#include <map> +#include <math.h> + +#include <ros/ros.h> +#include "sensor_msgs/LaserScan.h" +#include "geometry_msgs/Twist.h" +#include "std_msgs/Float64MultiArray.h" + +#include <music.hh> +#include <mpi.h> + +#include "sys/time.h" + +#include <iostream> + +#define DEBUG_OUTPUT false + +const double DEFAULT_TIMESTEP = 1e-3; +const double DEFAULT_SENSOR_UPDATE_RATE = 30; +const double DEFAULT_RTF = 1.0; +const std::string DEFAULT_ROS_NODE_NAME = "ros_sensor_node"; + +enum msg_types {Laserscan, Twist, Float64MultiArray}; + +class RosSensorAdapter +{ +public: + void init(int argc, char** argv); + bool ratesMatch (double precision); + void runMUSIC(); + void runROS(); + void runROSMUSIC(); + void finalize(); + +private: + std::string ros_topic; + ros::Subscriber subscriber; + std::string ros_node_name; + double rtf; + + MPI::Intracomm comm; + MUSIC::Setup* setup; + MUSIC::Runtime* runtime; + double stoptime; + int datasize; + double sensor_update_rate; + double timestep; + + pthread_mutex_t data_mutex; + double* data; + + msg_types msg_type; + + void initROS(int argc, char** argv); + void initMUSIC(int argc, char** argv); + + void laserscanCallback(const sensor_msgs::LaserScanConstPtr& msg); + void twistCallback(const geometry_msgs::Twist msg); + void float64MultiArrayCallback(const std_msgs::Float64MultiArray msg); + +}; diff --git a/ros/adapters/rtclock.cpp b/ros/adapters/rtclock.cpp new file mode 100644 index 0000000000000000000000000000000000000000..46d9fe07fd61b2e35e176488810dcbb72340ac80 --- /dev/null +++ b/ros/adapters/rtclock.cpp @@ -0,0 +1,71 @@ +/* + * rtclock.cpp + * + * Realtime clock + * + * Copyright (C) 2015 Mikael Djurfeldt + * + * rtclock is free software; you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * libneurosim is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see <http://www.gnu.org/licenses/>. + * + */ + +#include "rtclock.h" + +RTClock::RTClock (double interval = 0.) +{ + interval_ = timevalFromSeconds (interval); + reset (); +} + +void +RTClock::reset () +{ + gettimeofday (&start_, 0); + last_ = start_; +} + +double +RTClock::time () const +{ + struct timeval now; + gettimeofday (&now, 0); + timersub (&now, &start_, &now); + return secondsFromTimeval (now); +} + +void +RTClock::sleep (double t) const +{ + struct timespec req = timespecFromSeconds (t); + nanosleep (&req, NULL); +} + +void +RTClock::sleepNext () +{ + timeradd (&last_, &interval_, &last_); + struct timespec req = timespecFromTimeval (last_); + req.tv_sec = last_.tv_sec; + req.tv_nsec = 1000 * last_.tv_usec; + clock_nanosleep (CLOCK_REALTIME, TIMER_ABSTIME, &req, NULL); +} + +void +RTClock::sleepUntil (double t) const +{ + struct timeval goal = timevalFromSeconds (t); + timeradd (&start_, &goal, &goal); + struct timespec req = timespecFromTimeval (goal); + clock_nanosleep (CLOCK_REALTIME, TIMER_ABSTIME, &req, NULL); +} diff --git a/ros/adapters/rtclock.h b/ros/adapters/rtclock.h new file mode 100644 index 0000000000000000000000000000000000000000..8b0cd08310b87d0bc3d0c574ad6594b0e94857f7 --- /dev/null +++ b/ros/adapters/rtclock.h @@ -0,0 +1,130 @@ +/* -*- C++ -*- + * rtclock.h + * + * Realtime clock + * + * Copyright (C) 2015 Mikael Djurfeldt + * + * rtclock is free software; you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * libneurosim is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see <http://www.gnu.org/licenses/>. + * + */ + +#ifndef RTCLOCK_H +#define RTCLOCK_H + +#include <time.h> +#include <sys/time.h> + +class RTClock { +public: + /** + * Create a new RTClock and note the starting wallclock time which + * time () and sleepUntil (t) will use as a reference. + * + * If the optional interval is specified, this gives the sleeping + * time for the method sleepNext (). + */ + RTClock (double interval); + + /** + * Reset starting time. + * + * This resets the reference wallclock time for time () and + * sleepUntil (t). + */ + void reset (); + + /** + * Return the time in seconds since starting time. + */ + double time () const; + + /** + * Sleep t seconds. + */ + void sleep (double t) const; + + /** + * Sleep until next interval counting from start time. + * + * If wallclock time has passed since last interval, sleep shorter + * time such that we will wake up on a multiple of intervals from + * start time. + */ + void sleepNext (); + + /** + * Sleep until time t counting from start time. + */ + void sleepUntil (double t) const; + + /** + * Convert a (relative) time t in seconds to a timeval + */ + struct timeval timevalFromSeconds (double t) const; + + /** + * Convert a (relative) time tv to seconds + */ + double secondsFromTimeval (const struct timeval& tv) const; + + /** + * Convert a (relative) time t in seconds to a timespec + */ + struct timespec timespecFromSeconds (double s) const; + + /** + * Convert tv into a timespec struct + */ + struct timespec timespecFromTimeval (const struct timeval& tv) const; + +private: + struct timeval start_; + struct timeval last_; + struct timeval interval_; +}; + +inline struct timeval +RTClock::timevalFromSeconds (double t) const +{ + struct timeval tv; + tv.tv_sec = t; + tv.tv_usec = 1000000 * (t - tv.tv_sec); + return tv; +} + +inline double +RTClock::secondsFromTimeval (const struct timeval& tv) const +{ + return tv.tv_sec + 1e-6 * tv.tv_usec; +} + +inline struct timespec +RTClock::timespecFromSeconds (double t) const +{ + struct timespec ts; + ts.tv_sec = t; + ts.tv_nsec = 1e9 * (t - ts.tv_sec); + return ts; +} + +inline struct timespec +RTClock::timespecFromTimeval (const struct timeval& tv) const +{ + struct timespec ts; + ts.tv_sec = tv.tv_sec; + ts.tv_nsec = 1000 * tv.tv_usec; +} + +#endif /* RTCLOCK_H */ diff --git a/ros/decoder/Makefile.am b/ros/decoder/Makefile.am new file mode 100644 index 0000000000000000000000000000000000000000..faf109a8e7b6e36c51b98fadbb3909c1bd14c7fe --- /dev/null +++ b/ros/decoder/Makefile.am @@ -0,0 +1,13 @@ +bin_PROGRAMS = linear_readout_decoder + +AM_CXXFLAGS = -I$(top_srcdir) -I$(top_srcdir)/src -I$(top_builddir)/src @MPI_CXXFLAGS@ + +AM_LDFLAGS = $(top_builddir)/mpidep/libmpidep.la @MPI_LDFLAGS@ \ + $(top_builddir)/src/libmusic.la \ + $(top_builddir)/src/libmusic-c.la + + +linear_readout_decoder_SOURCES = linear_readout.h linear_readout.cpp +linear_readout_decoder_LDADD = -lgsl -lgslcblas -ljsoncpp + + diff --git a/ros/decoder/linear_readout.cpp b/ros/decoder/linear_readout.cpp new file mode 100644 index 0000000000000000000000000000000000000000..3bc5a450ce25829098600cb0d79a410f3a9ca3bd --- /dev/null +++ b/ros/decoder/linear_readout.cpp @@ -0,0 +1,237 @@ +/* + * This file is part of MUSIC. + * Copyright (C) 2016 INCF + * + * MUSIC is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * MUSIC is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see <http://www.gnu.org/licenses/>. + */ + +#include "linear_readout.h" + +int +main(int argc, char** argv) +{ + + LinearReadoutDecoder lin_decoder; + lin_decoder.init(argc, argv); + lin_decoder.runMUSIC(); + lin_decoder.finalize(); + +} + +void +LinearReadoutDecoder::init(int argc, char** argv) +{ + std::cout << "initializing linear readout decoder" << std::endl; + timestep = DEFAULT_TIMESTEP; + weights_filename = DEFAULT_WEIGHTS_FILENAME; + tau = DEFAULT_TAU; + num_spikes0 = 0; + + // init MUSIC to read config + initMUSIC(argc, argv); + readWeightsFile(); +} + +void +LinearReadoutDecoder::initMUSIC(int argc, char** argv) +{ + MUSIC::Setup* setup = new MUSIC::Setup (argc, argv); + + setup->config("stoptime", &stoptime); + setup->config("music_timestep", ×tep); + setup->config("weights_filename", &weights_filename); + setup->config("tau", &tau); + inv_tau = 1. / tau; + acceptable_latency = timestep; + + port_in = setup->publishEventInput("in"); + port_out = setup->publishContOutput("out"); + + comm = setup->communicator (); + int rank = comm.Get_rank (); + int nProcesses = comm.Get_size (); + if (nProcesses > 1) + { + std::cout << "ERROR: num processes (np) not equal 1" << std::endl; + comm.Abort(1); + } + + // get dimensions of sensory data and spike data + if (port_in->hasWidth() && port_out->hasWidth()) + { + size_spike_data = port_in->width(); + size_command_data = port_out->width(); + } + else + { + std::cout << "ERROR: Port-width not defined" << std::endl; + comm.Abort(1); + } + + command_data = new double[size_command_data]; + for (int i = 0; i < size_command_data; ++i) + { + command_data[i] = 0.; + } + vec_command_data = gsl_vector_view_array(command_data, size_command_data); + + activity_traces = new double[size_spike_data]; + for (int i = 0; i < size_spike_data; ++i) + { + activity_traces[i] = 0.; + } + vec_activity_traces = gsl_vector_view_array(activity_traces, size_spike_data); + + readout_weights = new double[size_command_data * size_spike_data]; + for (int i = 0; i < size_command_data * size_spike_data; ++i) + { + readout_weights[i] = 0.; + } + mat_readout_weights = gsl_matrix_view_array(readout_weights, size_command_data, size_spike_data); + + // Declare where in memory to put command_data + MUSIC::ArrayData dmap(command_data, + MPI::DOUBLE, + 0, + size_command_data); + port_out->map (&dmap, 1); + + // map linear index to event out port + MUSIC::LinearIndex l_index_in(0, size_spike_data); + port_in->map(&l_index_in, this, acceptable_latency, 1); + + // initialize propagator for exponential decay + propagator = std::exp(-timestep/tau); + + MPI::COMM_WORLD.Barrier(); + runtime = new MUSIC::Runtime (setup, timestep); +} + +void +LinearReadoutDecoder::readWeightsFile() +{ + Json::Reader json_reader; + + std::ifstream weights_file; + weights_file.open(weights_filename.c_str(), std::ios::in); + string json_weights = ""; + string line; + + while (std::getline(weights_file, line)) + { + json_weights += line; + } + weights_file.close(); + + if ( !json_reader.parse(json_weights, json_readout_weights)) + { + // report to the user the failure and their locations in the document. + std::cout << "WARNING: linear readout: Failed to parse file \"" << weights_filename << "\"\n" + << json_weights << " It has to be in JSON format.\n Using 1/N for each weight." + << json_reader.getFormattedErrorMessages(); + + for (int i = 0; i < size_command_data * size_spike_data; ++i) + { + readout_weights[i] = 1. / size_spike_data; + } + + return; + } + else + { + for (int i = 0; i < size_command_data; ++i) + { + for (int j = 0; j < size_spike_data; ++j) + { + readout_weights[i * size_spike_data + j] = json_readout_weights[i][j].asDouble(); + } + } + + } + +} + +void +LinearReadoutDecoder::runMUSIC() +{ + std::cout << "running linear readout decoder" << std::endl; + + int num_spikes_decoded = 0; + + struct timeval start; + struct timeval end; + gettimeofday(&start, NULL); + + double t = runtime->time(); + for (t = runtime->time (); t < stoptime; t = runtime->time ()) + { + double next_t = t + timestep; + while (!spikes.empty () && spikes.top ().t < next_t) + { + double t_spike = spikes.top ().t; + int id = spikes.top ().id; + + activity_traces[id] += (std::exp ((t_spike - t) * inv_tau) * inv_tau); + + spikes.pop (); // remove spike from queue + ++num_spikes_decoded; + } + + for (int j = 0; j < size_spike_data; ++j) + { + activity_traces[j] *= propagator; // decay + } + + gsl_blas_dgemv(CblasNoTrans, 1., &mat_readout_weights.matrix, &vec_activity_traces.vector, 0., &vec_command_data.vector); + +#if DEBUG_OUTPUT + std::cout << "Linear Readout: Activity Traces: "; + for (int i = 0; i < size_spike_data; ++i) + { + std::cout << activity_traces[i] << " "; + } + std::cout << std::endl; + + + std::cout << "Linear Readout: Command Data: "; + for (int i = 0; i < size_command_data; ++i) + { + std::cout << command_data[i] << " "; + } + std::cout << std::endl; +#endif + runtime->tick(); + } + + gettimeofday(&end, NULL); + unsigned int dt_s = end.tv_sec - start.tv_sec; + unsigned int dt_us = end.tv_usec - start.tv_usec; + if (end.tv_sec > start.tv_sec) + { + dt_us += 1000000; + } + std::cout << "decoder: total simtime: " << dt_s << " " << dt_us << " received spikes " << num_spikes0 << " spikes decoded " << num_spikes_decoded << std::endl; + +} + +void LinearReadoutDecoder::operator () (double t, MUSIC::GlobalIndex id){ + // Decoder: add incoming spikes to map + num_spikes0++; + + spikes.push (Event (t + acceptable_latency, id)); +} +void LinearReadoutDecoder::finalize(){ + runtime->finalize(); + delete runtime; +} diff --git a/ros/decoder/linear_readout.h b/ros/decoder/linear_readout.h new file mode 100644 index 0000000000000000000000000000000000000000..b6974c071a563c238bdaae9e6e3dee0b6d6df4b1 --- /dev/null +++ b/ros/decoder/linear_readout.h @@ -0,0 +1,88 @@ +/* -*- C++ -*- + * This file is part of MUSIC. + * Copyright (C) 2016 INCF + * + * MUSIC is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * MUSIC is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see <http://www.gnu.org/licenses/>. + */ + +#include <music.hh> +#include <mpi.h> + +#include <queue> +#include <cmath> +#include <unistd.h> +#include <iostream> +#include <fstream> +#include "sys/time.h" +#include "jsoncpp/json/json.h" + +#include <gsl/gsl_matrix_double.h> +#include <gsl/gsl_vector_double.h> +#include <gsl/gsl_blas.h> + +#include <iostream> + +#define DEBUG_OUTPUT false + +const double DEFAULT_TIMESTEP = 1e-3; +const double DEFAULT_TAU = 0.03; +const string DEFAULT_WEIGHTS_FILENAME = "readout_weights.dat"; + + +class LinearReadoutDecoder : MUSIC::EventHandlerGlobalIndex{ +public: + void init(int argc, char** argv); + void runMUSIC(); + void finalize(); + +private: + class Event { + public: + double t; + int id; + Event (double t_, int id_) : t (t_), id (id_) { } + bool operator< (const Event& other) const { return t > other.t; } + }; + + MPI::Intracomm comm; + MUSIC::Runtime* runtime; + double stoptime; + double timestep; + double acceptable_latency; + int size_command_data; + int size_spike_data; + double* command_data; + gsl_vector_view vec_command_data; + double* activity_traces; + gsl_vector_view vec_activity_traces; + unsigned int num_spikes0; + + string weights_filename; + Json::Value json_readout_weights; + double* readout_weights; + gsl_matrix_view mat_readout_weights; + + + MUSIC::EventInputPort* port_in; + MUSIC::ContOutputPort* port_out; + + double tau, inv_tau, propagator; + std::priority_queue<Event> spikes; + + void initMUSIC(int argc, char** argv); + void readWeightsFile(); + void operator() (double t, MUSIC::GlobalIndex id ); +}; + + diff --git a/ros/encoder/Makefile.am b/ros/encoder/Makefile.am new file mode 100644 index 0000000000000000000000000000000000000000..5da52d2feb0bb6dcaefbdd98494eea3aeb890877 --- /dev/null +++ b/ros/encoder/Makefile.am @@ -0,0 +1,19 @@ +bin_PROGRAMS = rate_encoder poisson_encoder nef_encoder + +AM_CXXFLAGS = -I$(top_srcdir) -I$(top_srcdir)/src -I$(top_builddir)/src @MPI_CXXFLAGS@ + +AM_LDFLAGS = $(top_builddir)/mpidep/libmpidep.la @MPI_LDFLAGS@ \ + $(top_builddir)/src/libmusic.la \ + $(top_builddir)/src/libmusic-c.la + + +rate_encoder_SOURCES = rate_encoder.h rate_encoder.cpp +rate_encoder_LDADD = + +poisson_encoder_SOURCES = poisson_encoder.h poisson_encoder.cpp +poisson_encoder_LDADD = + +nef_encoder_SOURCES = nef_encoder.h nef_encoder.cpp iaf_neuron.h +nef_encoder_LDADD = + + diff --git a/ros/encoder/iaf_neuron.h b/ros/encoder/iaf_neuron.h new file mode 100644 index 0000000000000000000000000000000000000000..223874d53604f92cf9cf757c6b994c25a1b066f4 --- /dev/null +++ b/ros/encoder/iaf_neuron.h @@ -0,0 +1,118 @@ +/* -*- C++ -*- + * This file is part of MUSIC. + * Copyright (C) 2016 INCF + * + * MUSIC is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * MUSIC is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see <http://www.gnu.org/licenses/>. + */ + +#include <iostream> +#include "stdlib.h" +#include <math.h> +#include <vector> +#include <numeric> + +class IAFNeuron{ + double tau_m, V_th, V_reset, I_e, C_m, R, resolution; + double t_ref;// refactory time in ms + int is_ref; // refactory time in steps + double propagator; + + // NEF parameters + std::vector<double> alpha; + bool is_nef_initialized; + +public: + double bias, V_m, scaling; + IAFNeuron(int dimensions){ + + //V_m = 0.0; + V_m = std::rand() % 10; + C_m = 250.0; + tau_m = 20.0; + V_th = 10.0; + V_reset = 0.0; + I_e = 0.0; + t_ref = 2; + + // dependent variables + R = tau_m / C_m; + + is_ref = 0.; + resolution = 0.0; + + // nef + init_nef(dimensions); + + } + + void setResolution(double resolution){ + this->resolution = resolution * 1000.; + propagator = std::exp(-(this->resolution)/tau_m); + } + + void encode(std::vector<double> data){ + I_e = std::inner_product(alpha.begin(), alpha.end(), data.begin(), bias); + + } + + bool propagate(){ + + if (propagator == 0){ + std::cerr << "Resolution not set. Call setResolution() first" << std::endl; + return false; + } + bool emit_spike = false; + + + if (is_ref == 0){ + //V_m += ((-(V_m-V_reset) + R * I_e) / tau_m ) * t; // forward euler? + V_m = R * (1 - propagator) * I_e + propagator * V_m; // exact! + + } + else{ + --is_ref; + } + + if (V_m > V_th){ + V_m = V_reset; + is_ref = int(t_ref/resolution); + emit_spike = true; + } + return emit_spike; + + } + +private: + void init_nef(int dimensions){ + std::vector<double> pref_direction; + double ssum = 0; + scaling = 0. + std::rand() % 300; + for (int i = 0; i < dimensions; ++i){ + double rand = std::rand() % 1000 / 1000. - 0.5; + ssum += rand * rand; + pref_direction.push_back(rand); + } + ssum = std::sqrt(ssum); + + for (int i = 0; i < dimensions; ++i){ + alpha.push_back((pref_direction.back() / ssum) * scaling); + pref_direction.pop_back(); + } + + bias = std::rand() % 200; + } + + + +}; diff --git a/ros/encoder/nef_encoder.cpp b/ros/encoder/nef_encoder.cpp new file mode 100644 index 0000000000000000000000000000000000000000..10ae2e349a94a433e0561a631fe25b87ccce225c --- /dev/null +++ b/ros/encoder/nef_encoder.cpp @@ -0,0 +1,170 @@ +/* + * This file is part of MUSIC. + * Copyright (C) 2016 INCF + * + * MUSIC is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * MUSIC is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see <http://www.gnu.org/licenses/>. + */ + +#include "nef_encoder.h" + +int +main(int argc, char** argv) +{ + + NefEncoder nef_encoder; + nef_encoder.init(argc, argv); + nef_encoder.runMUSIC(); + nef_encoder.finalize(); + +} + +void +NefEncoder::init(int argc, char** argv) +{ + std::cout << "initializing nef encoder" << std::endl; + timestep = DEFAULT_TIMESTEP; + initMUSIC(argc, argv); +} + +void +NefEncoder::initMUSIC(int argc, char** argv) +{ + MUSIC::Setup* setup = new MUSIC::Setup (argc, argv); + + setup->config("stoptime", &stoptime); + setup->config("music_timestep", ×tep); + + port_in = setup->publishContInput("in"); + port_out = setup->publishEventOutput("out"); + + comm = setup->communicator (); + int rank = comm.Get_rank (); + int nProcesses = comm.Get_size (); + if (nProcesses > 1) + { + std::cout << "ERROR: num processes (np) not equal 1" << std::endl; + comm.Abort(1); + } + + // get dimensions of sensory data and spike data + if (port_in->hasWidth() && port_out->hasWidth()) + { + size_sensor_data = port_in->width(); + size_spike_data = port_out->width(); + } + else + { + std::cout << "ERROR: Port-width not defined" << std::endl; + comm.Abort(1); + } + + for (unsigned int i = 0; i < size_sensor_data; ++i) + { + sensor_data.push_back(0.); + sensor_data_buf.push_back(0.); + } + + for (int n = 0; n < size_spike_data; ++n){ + IAFNeuron neuron(sensor_data.size()); + neuron.setResolution(DEFAULT_NEURON_RESOLUTION); + neurons.push_back(neuron); + neuron.encode(sensor_data); + } + + + // Declare where in memory to put sensor_data + MUSIC::ArrayData dmap(&sensor_data[0], + MPI::DOUBLE, + 0, + size_sensor_data); + port_in->map (&dmap, 0., 1, false); + + // map linear index to event out port + MUSIC::LinearIndex l_index_out(0, size_spike_data); + port_out->map(&l_index_out, MUSIC::Index::GLOBAL, 1); + + MPI::COMM_WORLD.Barrier(); + runtime = new MUSIC::Runtime (setup, timestep); +} + +void +NefEncoder::runMUSIC() +{ + std::cout << "running nef encoder" << std::endl; + + struct timeval start; + struct timeval end; + gettimeofday(&start, NULL); + int ticks_skipped = 0; + int _ticks_to_skip = 0; + + double t = runtime->time(); + while(t < stoptime) + { + t = runtime->time(); + + if (sensor_data != sensor_data_buf) + { + for (unsigned int n = 0; n < neurons.size(); ++n) + { + neurons[n].encode(sensor_data); + } + sensor_data_buf = sensor_data; + +#if DEBUG_OUTPUT + for (unsigned int n = 0; n < sensor_data.size(); ++n) + { + std::cout << sensor_data[n] << " "; + } + std::cout << std::endl; +#endif + } + + double next_t = t + timestep; + while (t <= next_t) + { + for (unsigned int n = 0; n < neurons.size(); ++n) + { + if (neurons[n].propagate()) + { +#if DEBUG_OUTPUT + // std::cout << "NEF Encoder: neuron " << n << " spiked at " << runtime->time() << std::endl; +#endif + port_out->insertEvent(runtime->time(), MUSIC::GlobalIndex(n)); + } + } + t += DEFAULT_NEURON_RESOLUTION; // propagate a ms + } + + runtime->tick(); + } + + gettimeofday(&end, NULL); + unsigned int dt_s = end.tv_sec - start.tv_sec; + unsigned int dt_us = end.tv_usec - start.tv_usec; + if (end.tv_sec > start.tv_sec) + { + dt_us += 1000000; + } + std::cout << "encoder: total simtime: " << dt_s << " " << dt_us << " ticks skipped " << ticks_skipped << std::endl; +} + +void NefEncoder::finalize(){ + runtime->finalize(); + delete runtime; +} + + + + diff --git a/ros/encoder/nef_encoder.h b/ros/encoder/nef_encoder.h new file mode 100644 index 0000000000000000000000000000000000000000..7afa851188bfaa7883be147d30141cc87bc20aff --- /dev/null +++ b/ros/encoder/nef_encoder.h @@ -0,0 +1,56 @@ +/* -*- C++ -*- + * This file is part of MUSIC. + * Copyright (C) 2016 INCF + * + * MUSIC is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * MUSIC is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see <http://www.gnu.org/licenses/>. + */ + +#include <music.hh> +#include <mpi.h> + +#include <vector> +#include <cmath> +#include <unistd.h> +#include "sys/time.h" + +#include "iaf_neuron.h" + +#define DEBUG_OUTPUT false + +const double DEFAULT_TIMESTEP = 1e-3; +const double DEFAULT_NEURON_RESOLUTION = 1e-3; + +class NefEncoder{ +public: + void init(int argc, char** argv); + void runMUSIC(); + void finalize(); + +private: + MPI::Intracomm comm; + MUSIC::Runtime* runtime; + double stoptime; + double timestep; + int size_sensor_data; + int size_spike_data; + std::vector<double> sensor_data; + std::vector<double> sensor_data_buf; + std::vector<IAFNeuron> neurons; + MUSIC::EventOutputPort* port_out; + MUSIC::ContInputPort* port_in; + + void initMUSIC(int argc, char** argv); +}; + + diff --git a/ros/encoder/poisson_encoder.cpp b/ros/encoder/poisson_encoder.cpp new file mode 100644 index 0000000000000000000000000000000000000000..66d9428cd4497286e254e7b499a3613993e516fd --- /dev/null +++ b/ros/encoder/poisson_encoder.cpp @@ -0,0 +1,171 @@ +/* + * This file is part of MUSIC. + * Copyright (C) 2016 INCF + * + * MUSIC is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * MUSIC is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see <http://www.gnu.org/licenses/>. + */ + +#include "poisson_encoder.h" + +int +main(int argc, char** argv) +{ + + RateEncoder poisson_encoder; + poisson_encoder.init(argc, argv); + poisson_encoder.runMUSIC(); + poisson_encoder.finalize(); + +} + +void +RateEncoder::init(int argc, char** argv) +{ + std::cout << "initializing poisson encoder" << std::endl; + timestep = DEFAULT_TIMESTEP; + rate_min = DEFAULT_RATE_MIN; + rate_max = DEFAULT_RATE_MAX; + initMUSIC(argc, argv); +} + +void +RateEncoder::initMUSIC(int argc, char** argv) +{ + MUSIC::Setup* setup = new MUSIC::Setup (argc, argv); + + setup->config("stoptime", &stoptime); + setup->config("music_timestep", ×tep); + setup->config("rate_min", &rate_min); + setup->config("rate_max", &rate_max); + normalization_factor = (rate_max - rate_min) / 2.; + + port_in = setup->publishContInput("in"); + port_out = setup->publishEventOutput("out"); + + comm = setup->communicator (); + int rank = comm.Get_rank (); + int nProcesses = comm.Get_size (); + if (nProcesses > 1) + { + std::cout << "ERROR: num processes (np) not equal 1" << std::endl; + comm.Abort(1); + } + + // get dimensions of sensory data and spike data + if (port_in->hasWidth() && port_out->hasWidth()) + { + size_data = port_in->width(); + } + else + { + std::cout << "ERROR: Port-width not defined" << std::endl; + comm.Abort(1); + } + + rates = new double[size_data]; + rates_buf = new double[size_data]; + next_spike = new double[size_data]; + for (int i = 0; i < size_data; ++i) + { + rates[i] = 0.; + rates_buf[i] = 0.; + next_spike[i] = negexp(denormalize(rates[i])); + } + + // Declare where in memory to put sensor_data + MUSIC::ArrayData dmap(rates, + MPI::DOUBLE, + 0, + size_data); + port_in->map (&dmap, 0., 1, false); + + // map linear index to event out port + MUSIC::LinearIndex l_index_out(0, size_data); + port_out->map(&l_index_out, MUSIC::Index::GLOBAL, 1); + + MPI::COMM_WORLD.Barrier(); + runtime = new MUSIC::Runtime (setup, timestep); +} + +void +RateEncoder::runMUSIC() +{ + std::cout << "running poisson encoder" << std::endl; + + struct timeval start; + struct timeval end; + gettimeofday(&start, NULL); + int ticks_skipped = 0; + double t = runtime->time(); + + while(t < stoptime) + { + t = runtime->time(); + + for (int n = 0; n < size_data; ++n) + { + if (rates[n] != rates_buf[n]) + { + next_spike[n] = t + negexp(denormalize(rates[n])); + rates_buf[n] = rates[n]; + } + + while(next_spike[n] < t + timestep) + { +#if DEBUG_OUTPUT + std::cout << "Poisson Encoder: neuron " << n << " spiked at " << runtime->time() << std::endl; +#endif + port_out->insertEvent(runtime->time(), MUSIC::GlobalIndex(n)); + next_spike[n] += negexp(denormalize(rates[n])); + } + } + + runtime->tick(); + } + + gettimeofday(&end, NULL); + unsigned int dt_s = end.tv_sec - start.tv_sec; + unsigned int dt_us = end.tv_usec - start.tv_usec; + if (end.tv_sec > start.tv_sec) + { + dt_us += 1000000; + } + std::cout << "poisson encoder: total simtime: " << dt_s << " " << dt_us << " ticks skipped " << ticks_skipped << std::endl; +} + +inline double +RateEncoder::denormalize(double s) +{ + // incoming data is normalized between -1 and 1 + // + // returns interspike interval with rate between [min_rate, max_rate] + + return 1. / ((s+1) * normalization_factor + rate_min); +} + +double +RateEncoder::negexp (double m) +{ + return - m * log (drand48 ()); +} + +void +RateEncoder::finalize(){ + runtime->finalize(); + delete runtime; +} + + + + diff --git a/ros/encoder/poisson_encoder.h b/ros/encoder/poisson_encoder.h new file mode 100644 index 0000000000000000000000000000000000000000..fc592c50f01caedbba811dca2f05a63711913ca7 --- /dev/null +++ b/ros/encoder/poisson_encoder.h @@ -0,0 +1,59 @@ +/* -*- C++ -*- + * This file is part of MUSIC. + * Copyright (C) 2016 INCF + * + * MUSIC is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * MUSIC is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see <http://www.gnu.org/licenses/>. + */ + +#include <music.hh> +#include <mpi.h> + +#include <vector> +#include <cmath> +#include <unistd.h> +#include "sys/time.h" + +#define DEBUG_OUTPUT false + +const double DEFAULT_TIMESTEP = 1e-3; +const double DEFAULT_RATE_MIN = 0.; +const double DEFAULT_RATE_MAX = 100.; + +class RateEncoder{ +public: + void init(int argc, char** argv); + void runMUSIC(); + void finalize(); + +private: + MPI::Intracomm comm; + MUSIC::Runtime* runtime; + double stoptime; + double timestep; + int size_data; + double normalization_factor; + + double rate_min, rate_max; + double* next_spike; + double* rates; + double* rates_buf; + MUSIC::EventOutputPort* port_out; + MUSIC::ContInputPort* port_in; + + void initMUSIC(int argc, char** argv); + double denormalize(double s); + double negexp (double m); +}; + + diff --git a/ros/encoder/rate_encoder.cpp b/ros/encoder/rate_encoder.cpp new file mode 100644 index 0000000000000000000000000000000000000000..6fffc6cb8a854d08a3654deb0ce2d3dfe553a0d7 --- /dev/null +++ b/ros/encoder/rate_encoder.cpp @@ -0,0 +1,184 @@ +/* + * This file is part of MUSIC. + * Copyright (C) 2016 INCF + * + * MUSIC is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * MUSIC is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see <http://www.gnu.org/licenses/>. + */ + +#include "rate_encoder.h" + +int +main(int argc, char** argv) +{ + + RateEncoder rate_encoder; + rate_encoder.init(argc, argv); + rate_encoder.runMUSIC(); + rate_encoder.finalize(); + +} + +void +RateEncoder::init(int argc, char** argv) +{ + std::cout << "initializing rate encoder" << std::endl; + timestep = DEFAULT_TIMESTEP; + rate_min = DEFAULT_RATE_MIN; + rate_max = DEFAULT_RATE_MAX; + initMUSIC(argc, argv); +} + +void +RateEncoder::initMUSIC(int argc, char** argv) +{ + MUSIC::Setup* setup = new MUSIC::Setup (argc, argv); + + setup->config("stoptime", &stoptime); + setup->config("music_timestep", ×tep); + setup->config("rate_min", &rate_min); + setup->config("rate_max", &rate_max); + normalization_factor = (rate_max - rate_min) / 2.; + + port_in = setup->publishContInput("in"); + port_out = setup->publishEventOutput("out"); + + comm = setup->communicator (); + int rank = comm.Get_rank (); + int nProcesses = comm.Get_size (); + if (nProcesses > 1) + { + std::cout << "ERROR: num processes (np) not equal 1" << std::endl; + comm.Abort(1); + } + + // get dimensions of sensory data and spike data + if (port_in->hasWidth() && port_out->hasWidth()) + { + size_data = port_in->width(); + } + else + { + std::cout << "ERROR: Port-width not defined" << std::endl; + comm.Abort(1); + } + + rates = new double[size_data]; + rates_buf = new double[size_data]; + next_spike = new double[size_data]; + last_spike = new double[size_data]; + for (int i = 0; i < size_data; ++i) + { + rates[i] = -1.; + rates_buf[i] = -1.; + last_spike[i] = 0.; + next_spike[i] = rate2SpikeTime(rates[i]); + } + + // Declare where in memory to put sensor_data + MUSIC::ArrayData dmap(rates, + MPI::DOUBLE, + 0, + size_data); + port_in->map (&dmap, 0., 1, false); + + // map linear index to event out port + MUSIC::LinearIndex l_index_out(0, size_data); + port_out->map(&l_index_out, MUSIC::Index::GLOBAL, 1); + + MPI::COMM_WORLD.Barrier(); + runtime = new MUSIC::Runtime (setup, timestep); +} + +void +RateEncoder::runMUSIC() +{ + std::cout << "running rate encoder" << std::endl; + + struct timeval start; + struct timeval end; + gettimeofday(&start, NULL); + int ticks_skipped = 0; + unsigned int num_spikes = 0; + + double t = runtime->time(); + while(t < stoptime) + { + t = runtime->time(); + + double next_t = t + timestep; + for (int n = 0; n < size_data; ++n) + { + if (rates[n] != rates_buf[n]) + { + double old_isi = next_spike[n] - last_spike[n]; + double part_time_left = (t - last_spike[n]) / old_isi; + double new_isi = rate2SpikeTime(rates[n]) * (1 - part_time_left); + next_spike[n] = t + new_isi; + rates_buf[n] = rates[n]; + } + + + while(next_spike[n] < next_t) + { +#if DEBUG_OUTPUT + std::cout << "Rate Encoder: neuron " << n << " spikes at " << next_spike[n] << " simtime: " << t << " rate " << rates[n] << std::endl; +#endif + num_spikes++; + port_out->insertEvent(next_spike[n], MUSIC::GlobalIndex(n)); + last_spike[n] = next_spike[n]; + next_spike[n] += rate2SpikeTime(rates[n]); + } + } + //#if DEBUG_OUTPUT + // std::cout << "Rate Encoder: "; + // for (int i = 0; i < size_data; ++i) + // { + // std::cout << rates[i] << " " << rates_buf[i] << " "; + // } + // std::cout << std::endl; + //#endif + + runtime->tick(); + } + + gettimeofday(&end, NULL); + unsigned int dt_s = end.tv_sec - start.tv_sec; + unsigned int dt_us = end.tv_usec - start.tv_usec; + if (end.tv_sec > start.tv_sec) + { + dt_us += 1000000; + } + std::cout << "rate encoder: total simtime: " << dt_s << " " << dt_us << " ticks skipped " << ticks_skipped << " num spikes " << num_spikes << std::endl; +} + +double +RateEncoder::rate2SpikeTime(double r) +{ + // the incoming data, which is interpreted as rate, is between -1 and 1. + // + // scales rate between [rate_min, rate_max] + // + // returns next spike time + return 1. / ((r+1) * normalization_factor + rate_min); +} + +void +RateEncoder::finalize(){ + runtime->finalize(); + delete runtime; +} + + + + diff --git a/ros/encoder/rate_encoder.h b/ros/encoder/rate_encoder.h new file mode 100644 index 0000000000000000000000000000000000000000..12e18a9d60bd65056cf64cddc7c5cb659deff775 --- /dev/null +++ b/ros/encoder/rate_encoder.h @@ -0,0 +1,61 @@ +/* -*- C++ -*- + * This file is part of MUSIC. + * Copyright (C) 2016 INCF + * + * MUSIC is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * MUSIC is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see <http://www.gnu.org/licenses/>. + */ + +#include <music.hh> +#include <mpi.h> + +#include <vector> +#include <cmath> +#include <unistd.h> +#include "sys/time.h" + +#define DEBUG_OUTPUT false + +const double DEFAULT_TIMESTEP = 1e-3; +const double DEFAULT_RATE_MIN = 0.; +const double DEFAULT_RATE_MAX = 100.; + + +class RateEncoder{ +public: + void init(int argc, char** argv); + void runMUSIC(); + void finalize(); + +private: + MPI::Intracomm comm; + MUSIC::Runtime* runtime; + double stoptime; + double timestep; + int size_data; + double normalization_factor; + + double rate_min, rate_max; + double* next_spike; + double* last_spike; + double* rates; + double* rates_buf; + MUSIC::EventOutputPort* port_out; + MUSIC::ContInputPort* port_in; + + void initMUSIC(int argc, char** argv); + + inline double rate2SpikeTime(double r); +}; + + diff --git a/ros/examples/README.txt b/ros/examples/README.txt new file mode 100644 index 0000000000000000000000000000000000000000..c1badf2f3a1cb244c7a48ff4204b37391a607575 --- /dev/null +++ b/ros/examples/README.txt @@ -0,0 +1,5 @@ +The Braitenberg is dependent on a predefined robot "Pioneer3AT"". +How to install and use the Pioneer3AT, please read the ROS tutorials at http://wiki.ros.org/ROS/Tutorials. + +Please read the HOWTO on https://github.com/weidel-p/ros_music_adapter. + diff --git a/ros/examples/braitenberg3/braitenberg3.music b/ros/examples/braitenberg3/braitenberg3.music new file mode 100644 index 0000000000000000000000000000000000000000..9275eb1dd20716f3570643e0270832a532d87710 --- /dev/null +++ b/ros/examples/braitenberg3/braitenberg3.music @@ -0,0 +1,46 @@ +stoptime=1000. +[sensor] + binary=ros_sensor_adapter + args= + np=1 + music_timestep=0.05 + ros_topic=/Pioneer3AT/laserscan + message_type=Laserscan + sensor_update_rate=20 +[converge] + binary=connect_adapter + args= + np=1 + music_timestep=0.05 + weights_filename=braitenberg3_converge_weights.dat +[encoder] + binary=rate_encoder + args= + np=1 + music_timestep=0.05 + rate_min=1 + rate_max=200 +[nest] + binary=./braitenberg3_pyNEST.py + args=-s 0.05 -t 1000 -n 2 + np=1 +[decoder] + binary=linear_readout_decoder + args= + np=1 + music_timestep=0.05 + tau=0.03 + weights_filename=braitenberg3_readout_weights.dat +[command] + binary=ros_command_adapter + args= + np=1 + music_timestep=0.05 + ros_topic=/Pioneer3AT/cmd_vel + message_mapping_filename=braitenberg3_twist_mapping.dat + command_rate=20 +sensor.out->converge.in[20] +converge.out->encoder.in[2] +encoder.out->nest.in[2] +nest.out->decoder.in[2] +decoder.out->command.in[2] diff --git a/ros/examples/braitenberg3/braitenberg3_converge_weights.dat b/ros/examples/braitenberg3/braitenberg3_converge_weights.dat new file mode 100644 index 0000000000000000000000000000000000000000..982f2dd7aa9e6cc711b49b3f3954b06ea10b4695 --- /dev/null +++ b/ros/examples/braitenberg3/braitenberg3_converge_weights.dat @@ -0,0 +1 @@ +[[0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1]] \ No newline at end of file diff --git a/ros/examples/braitenberg3/braitenberg3_float_mapping.dat b/ros/examples/braitenberg3/braitenberg3_float_mapping.dat new file mode 100644 index 0000000000000000000000000000000000000000..01a3d3ae0f169f984c6b4815e09b30bfd2268e25 --- /dev/null +++ b/ros/examples/braitenberg3/braitenberg3_float_mapping.dat @@ -0,0 +1 @@ +{"message_type": "Float64MultiArray"} \ No newline at end of file diff --git a/ros/examples/braitenberg3/braitenberg3_pyNEST.py b/ros/examples/braitenberg3/braitenberg3_pyNEST.py new file mode 100755 index 0000000000000000000000000000000000000000..1284de716490512d4e2369245ef74f3112eaf59a --- /dev/null +++ b/ros/examples/braitenberg3/braitenberg3_pyNEST.py @@ -0,0 +1,55 @@ +#!/usr/bin/python + +import nest +import numpy as np +import sys +from datetime import datetime +from optparse import OptionParser +from mpi4py import MPI + +comm = MPI.COMM_WORLD + +to_ms = lambda t: t * 1000. + +opt_parser = OptionParser() +opt_parser.add_option("-t", "--simtime", dest="simtime", type="float", help="Simulation time in s") +opt_parser.add_option("-s", "--timestep", dest="music_timestep", type="float", help="MUSIC timestep") +opt_parser.add_option("-n", "--num_neurons", dest="num_neurons", type="int", help="Number of encoding neurons") + +(options, args) = opt_parser.parse_args() + +nest.ResetKernel() +nest.set_verbosity("M_FATAL") +nest.SetKernelStatus({'resolution': 1.0}) +#nest.SetKernelStatus({'print_time': True}) + +NUM_ENC_NEURONS = options.num_neurons + +proxy_in = nest.Create('music_event_in_proxy', NUM_ENC_NEURONS) +nest.SetStatus(proxy_in, [{'port_name': 'in', 'music_channel': c} for c in range(NUM_ENC_NEURONS)]) +nest.SetAcceptableLatency('in', to_ms(options.music_timestep)) + +proxy_out = nest.Create('music_event_out_proxy') +nest.SetStatus(proxy_out, {'port_name': 'out'}) + +parrot = nest.Create("parrot_neuron", NUM_ENC_NEURONS) + +nest.Connect(proxy_in, parrot, 'one_to_one', {'delay': to_ms(options.music_timestep)}) +for i in range(NUM_ENC_NEURONS): + nest.Connect([parrot[i]], proxy_out, 'all_to_all', {'music_channel': i, 'delay': to_ms(options.music_timestep)}) + +comm.Barrier() +start = datetime.now() + +nest.Simulate(to_ms(options.simtime)) + +end = datetime.now() +dt = end - start +run_time = dt.seconds + dt.microseconds / 1000000. + +print +print +print "RUN TIME:", run_time +print +print + diff --git a/ros/examples/braitenberg3/braitenberg3_readout_weights.dat b/ros/examples/braitenberg3/braitenberg3_readout_weights.dat new file mode 100644 index 0000000000000000000000000000000000000000..86c7d2d527653d14cf83ae40da16d2b66c267e63 --- /dev/null +++ b/ros/examples/braitenberg3/braitenberg3_readout_weights.dat @@ -0,0 +1 @@ +[[0.001, 0.001], [-0.003, 0.003]] diff --git a/ros/examples/braitenberg3/braitenberg3_twist_mapping.dat b/ros/examples/braitenberg3/braitenberg3_twist_mapping.dat new file mode 100644 index 0000000000000000000000000000000000000000..dde191474db19495124515e0e69923fed0a831c0 --- /dev/null +++ b/ros/examples/braitenberg3/braitenberg3_twist_mapping.dat @@ -0,0 +1 @@ +{"message_type": "Twist", "mapping": {"angular.z": 1, "linear.x": 0}} \ No newline at end of file