Public Member Functions | Private Member Functions | Private Attributes
CatCreator Class Reference

Node for creating CATs (center of activity trajectories) More...

#include <cat_creator.h>

List of all members.

Public Member Functions

 CatCreator ()
 ~CatCreator ()
 Closes the log file before the object is destroyed.

Private Member Functions

bool caExists (const neuro_recv::dish_state &d)
 Checks if a center of activity exists in a dish state.
void callback (const burst_calc::burst::ConstPtr &b)
 Callback for burst messages.
const burst_calc::ca getCa (const neuro_recv::dish_state &d)
 Generates a CA (center of activity) from a dish state.
void getParams ()
 Gets server parameters.
void headerToFile (const burst_calc::burst &b)
 Writes a header for a burst to the log file.
void init ()
 Initializes the node.
void initFile (const char *cat_file)
 Initializes a new CSV log file for recording CATs.
void rangesCallback (const burst_calc::ranges::ConstPtr &r)
 Callback for range messages.
void toFile (int i, const neuro_recv::dish_state &d, const burst_calc::ca &c)
 Writes a dish state and its center of activity to the log file.
void toFile (int i, const neuro_recv::dish_state &d)
 Writes a dish state with no center of activity to the log file.
void updateOffsets (const neuro_recv::dish_state &d)
 Updates the offsets for each each channel.

Private Attributes

ros::Subscriber burst_sub_
ros::Publisher ca_pub_
std::ofstream cat_file_
ros::Publisher cat_pub_
std::string file_name_
bool is_init_
ros::NodeHandle n_
double offsets_ [60]
ros::Subscriber ranges_sub_
bool save_to_file_
double thresholds_ [60]

Detailed Description

Node for creating CATs (center of activity trajectories)

This node receives bursts from the burst creator node and calculates a CAT for each burst. It then publishes the CAT to the dish teleop node for ARM movement.

The CAT metric is described in this paper:

Chao ZC, Bakkum DJ, Potter SM (2007). "Region-specific network plasticity in simulated and living cortical networks: comparison of the Center of Activity Trajectory (CAT) with other metrics." J. Neural Eng. 4, 294-308.

Author:
Jonathan Hasenzahl

Definition at line 52 of file cat_creator.h.


Constructor & Destructor Documentation

CatCreator::CatCreator ( ) [inline]

Definition at line 55 of file cat_creator.h.

Closes the log file before the object is destroyed.

Definition at line 13 of file cat_creator.cpp.


Member Function Documentation

bool CatCreator::caExists ( const neuro_recv::dish_state &  d) [private]

Checks if a center of activity exists in a dish state.

CA can only be calculated from spiking activity.

Parameters:
dthe dish state to be checked
Returns:
true if at least 1 spike exists in the dish state, false otherwise

Definition at line 181 of file cat_creator.cpp.

void CatCreator::callback ( const burst_calc::burst::ConstPtr &  b) [private]

Callback for burst messages.

This method is called automatically when the node receives a burst message. It creates and publishes a CAT from this burst.

Parameters:
bthe received message

Definition at line 96 of file cat_creator.cpp.

const burst_calc::ca CatCreator::getCa ( const neuro_recv::dish_state &  d) [private]

Generates a CA (center of activity) from a dish state.

Center of activity = summation(position*activity) / total activity

Parameters:
dthe source dish state
Returns:
the new CA

Definition at line 202 of file cat_creator.cpp.

void CatCreator::getParams ( ) [private]

Gets server parameters.

Definition at line 56 of file cat_creator.cpp.

void CatCreator::headerToFile ( const burst_calc::burst &  b) [private]

Writes a header for a burst to the log file.

Parameters:
bthe burst being logged

Definition at line 271 of file cat_creator.cpp.

void CatCreator::init ( ) [private]

Initializes the node.

Gets server parameters, initializes publishers and subscribers, starts the log file, and runs the spin loop.

Definition at line 26 of file cat_creator.cpp.

void CatCreator::initFile ( const char *  cat_file) [private]

Initializes a new CSV log file for recording CATs.

Parameters:
cat_filethe path of the file

Definition at line 249 of file cat_creator.cpp.

void CatCreator::rangesCallback ( const burst_calc::ranges::ConstPtr &  r) [private]

Callback for range messages.

This method is called automatically when the node receives a range message. This should only happen once. The values in the message are used to calculate the initial offsets.

Parameters:
rthe received message

Definition at line 152 of file cat_creator.cpp.

void CatCreator::toFile ( int  i,
const neuro_recv::dish_state &  d,
const burst_calc::ca &  c 
) [private]

Writes a dish state and its center of activity to the log file.

Parameters:
dthe dish state being logged
cthe CA being logged

Definition at line 286 of file cat_creator.cpp.

void CatCreator::toFile ( int  i,
const neuro_recv::dish_state &  d 
) [private]

Writes a dish state with no center of activity to the log file.

Parameters:
dthe dish state being logged

Definition at line 300 of file cat_creator.cpp.

void CatCreator::updateOffsets ( const neuro_recv::dish_state &  d) [private]

Updates the offsets for each each channel.

To account for negative voltages, each channel has an offset so that the smallest voltage effectively becomes zero, and all higher voltages are positive. This method checks the voltages of each incoming dish state and updates the offsets if necessary.

Parameters:
dthe dish state to check

Definition at line 76 of file cat_creator.cpp.


Member Data Documentation

ros::Subscriber CatCreator::burst_sub_ [private]

Definition at line 73 of file cat_creator.h.

ros::Publisher CatCreator::ca_pub_ [private]

Definition at line 76 of file cat_creator.h.

std::ofstream CatCreator::cat_file_ [private]

Definition at line 77 of file cat_creator.h.

ros::Publisher CatCreator::cat_pub_ [private]

Definition at line 75 of file cat_creator.h.

std::string CatCreator::file_name_ [private]

Definition at line 78 of file cat_creator.h.

bool CatCreator::is_init_ [private]

Definition at line 82 of file cat_creator.h.

ros::NodeHandle CatCreator::n_ [private]

Definition at line 72 of file cat_creator.h.

double CatCreator::offsets_[60] [private]

Definition at line 79 of file cat_creator.h.

ros::Subscriber CatCreator::ranges_sub_ [private]

Definition at line 74 of file cat_creator.h.

bool CatCreator::save_to_file_ [private]

Definition at line 81 of file cat_creator.h.

double CatCreator::thresholds_[60] [private]

Definition at line 80 of file cat_creator.h.


The documentation for this class was generated from the following files:


burst_calc
Author(s): Jonathan Hasenzahl
autogenerated on Sun Jan 5 2014 11:12:30