Public Member Functions | Private Member Functions | Private Attributes | List of all members
ModBridge Class Reference

Public Member Functions

 ModBridge ()
 
void spin ()
 

Private Member Functions

void controllerCallback (const modelica_bridge::ModComm::ConstPtr &inVal)
 
void error (const char *msg)
 
void readFromBuffer ()
 
void writeToBuffer ()
 

Private Attributes

char buffer_ [MAX_BUF]
 string buffer used to transmit information over the socket More...
 
struct sockaddr_in client_address_
 Modelica socket address. More...
 
socklen_t client_len_
 Modelica socket size. More...
 
int error_check_
 Parameter for checking errors on socket interaction. More...
 
int new_socket_fd_
 Modelica socket binding. More...
 
ros::NodeHandle nh_
 ROS node handle. More...
 
int port_num_
 Port number. More...
 
ros::Publisher pub_
 publisher for model feedback values More...
 
double ros_buffer_ [MAX_ARRAY]
 buffer array for transmission via ROS More...
 
struct sockaddr_in serv_addr
 ROS socket address. More...
 
double socket_buffer_ [MAX_ARRAY]
 buffer array for interaction with socket More...
 
int socket_fd_
 ROS socket binding. More...
 
ros::Subscriber sub_
 subscriber to ROS controller values More...
 
int update_rate_
 ROS node maximum loop rate. More...
 

Detailed Description

Class to act as relay between ROS and Modelica. It initializes a tcp/ip socket to act as a bridge between ROS and Modelica. It can take character buffers up to 1024 bytes.

Definition at line 44 of file modbridge_node.cpp.

Constructor & Destructor Documentation

ModBridge::ModBridge ( )

Defult constructor initializes receiving socket, subs and pubs. No inputs.

Returns
none

Definition at line 118 of file modbridge_node.cpp.

Member Function Documentation

void ModBridge::controllerCallback ( const modelica_bridge::ModComm::ConstPtr &  inVal)
private

Callback for receiving controller values. Reads from topic /control_values. Stores data into array of size MAX_ARRAY - only reads MAX_ARRAY amount of array slots.

Parameters
[in]inValModComm message holding controller values.
Returns
none

Definition at line 186 of file modbridge_node.cpp.

void ModBridge::error ( const char *  msg)
private

Prints error message when interacting with socket.

Parameters
[in]msgerror message
See also
error_check_()
Returns
none

Definition at line 222 of file modbridge_node.cpp.

void ModBridge::readFromBuffer ( )
private

Breaks up the incoming character buffer into data array. Splits the character buffer into an array of tokens of data. The first token is the size of the array.

See also
buffer_()
ros_buffer_()
writeToBuffer()
Returns
none

Definition at line 194 of file modbridge_node.cpp.

void ModBridge::spin ( )

Keep program from closing. Run callbacks for ROS nodes, and keep socket connection to Modelica alive. No inputs.

Returns
none

Definition at line 142 of file modbridge_node.cpp.

void ModBridge::writeToBuffer ( )
private

Concatenates the control values into a character buffer.

See also
readFromBuffer()
buffer_()
socket_buffer_()
Returns
none

Definition at line 211 of file modbridge_node.cpp.

Member Data Documentation

char ModBridge::buffer_[MAX_BUF]
private

string buffer used to transmit information over the socket

Definition at line 110 of file modbridge_node.cpp.

struct sockaddr_in ModBridge::client_address_
private

Modelica socket address.

Definition at line 108 of file modbridge_node.cpp.

socklen_t ModBridge::client_len_
private

Modelica socket size.

Definition at line 107 of file modbridge_node.cpp.

int ModBridge::error_check_
private

Parameter for checking errors on socket interaction.

Definition at line 115 of file modbridge_node.cpp.

int ModBridge::new_socket_fd_
private

Modelica socket binding.

Definition at line 104 of file modbridge_node.cpp.

ros::NodeHandle ModBridge::nh_
private

ROS node handle.

Definition at line 99 of file modbridge_node.cpp.

int ModBridge::port_num_
private

Port number.

Definition at line 105 of file modbridge_node.cpp.

ros::Publisher ModBridge::pub_
private

publisher for model feedback values

Definition at line 101 of file modbridge_node.cpp.

double ModBridge::ros_buffer_[MAX_ARRAY]
private

buffer array for transmission via ROS

Definition at line 112 of file modbridge_node.cpp.

struct sockaddr_in ModBridge::serv_addr
private

ROS socket address.

Definition at line 106 of file modbridge_node.cpp.

double ModBridge::socket_buffer_[MAX_ARRAY]
private

buffer array for interaction with socket

Definition at line 111 of file modbridge_node.cpp.

int ModBridge::socket_fd_
private

ROS socket binding.

Definition at line 103 of file modbridge_node.cpp.

ros::Subscriber ModBridge::sub_
private

subscriber to ROS controller values

Definition at line 100 of file modbridge_node.cpp.

int ModBridge::update_rate_
private

ROS node maximum loop rate.

Definition at line 113 of file modbridge_node.cpp.


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


modelica_bridge
Author(s):
autogenerated on Mon Jun 10 2019 13:54:27