Skip to content

Commit

Permalink
dev
Browse files Browse the repository at this point in the history
  • Loading branch information
1r0b1n0 committed Oct 26, 2017
1 parent 2ef03f4 commit 4a8bb79
Show file tree
Hide file tree
Showing 6 changed files with 48 additions and 32 deletions.
2 changes: 1 addition & 1 deletion scripts/make_library.py
Original file line number Diff line number Diff line change
Expand Up @@ -460,7 +460,7 @@ def _write_deserializer(self, f):
f.write(' size_t offset = 0;\n')
for d in self.data:
d.deserialize(f)
f.write(' return offset;\n');
f.write(' return offset;\n');
f.write(' }\n')
f.write('\n')

Expand Down
35 changes: 20 additions & 15 deletions src/ros_lib/RosQtSocket.cpp
Original file line number Diff line number Diff line change
@@ -1,46 +1,51 @@
#include "ros/RosQtSocket.h"

#define DEFAULT_PORT 11411

using std::string;
using std::cerr;
using std::endl;


RosQtSocket::RosQtSocket(QObject *parent):
QObject(parent)
QObject(parent),
socket_valid_(false)
{
QObject::connect(&m_socket, SIGNAL(readyRead()), this, SIGNAL(readyRead()));
QObject::connect(&m_socket, SIGNAL(connected()), this, SLOT(onConnected()));
QObject::connect(&socket_, SIGNAL(readyRead()), this, SIGNAL(readyRead()));
QObject::connect(&socket_, SIGNAL(connected()), this, SLOT(onConnected()));
}

void RosQtSocket::doConnect()
{
if(m_socket.state() == QAbstractSocket::UnconnectedState)
if(socket_.state() == QAbstractSocket::UnconnectedState)
{
m_socket.connectToHost(m_address, m_port);
socket_.connectToHost(address_, port_);
}

}

void RosQtSocket::init(const std::string &server_hostname)
void RosQtSocket::open(const std::string &server_hostname, uint16_t port)
{
m_address = QHostAddress(QString::fromStdString(server_hostname));
m_port = DEFAULT_PORT;
socket_valid_ = true;
address_ = QHostAddress(QString::fromStdString(server_hostname));
port_ = port;

doConnect();
}

void RosQtSocket::close()
{
socket_.close();
}

int64_t RosQtSocket::read(unsigned char *data, int max_length)
{
if(m_socket.state() != QAbstractSocket::ConnectedState)
if(socket_.state() != QAbstractSocket::ConnectedState)
{
std::cerr << "Failed to receive data from server, not connected " << std::endl;
doConnect();
return -1;
}

int64_t result = m_socket.read((char*)data, max_length);
int64_t result = socket_.read((char*)data, max_length);
if(result < 0)
{
std::cerr << "Failed to receive data from server" << std::endl;
Expand All @@ -52,15 +57,15 @@ int64_t RosQtSocket::read(unsigned char *data, int max_length)

bool RosQtSocket::write(const unsigned char *data, int length)
{
if(m_socket.state() != QAbstractSocket::ConnectedState)
if(socket_valid_ && socket_.state() != QAbstractSocket::ConnectedState)
{
std::cerr << "Failed to write data to the server, not connected " << std::endl;
doConnect();
return false;
}
else
{
qint64 result = m_socket.write((const char*)data, length);
qint64 result = socket_.write((const char*)data, length);
if(result != length)
{
std::cerr << "Failed to write all the data to the server" << std::endl;
Expand All @@ -78,5 +83,5 @@ unsigned long RosQtSocket::time()

void RosQtSocket::onConnected()
{
m_socket.setSocketOption(QAbstractSocket::LowDelayOption, 1);
socket_.setSocketOption(QAbstractSocket::LowDelayOption, 1);
}
11 changes: 7 additions & 4 deletions src/ros_lib/ros/RosQtSocket.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,9 @@ class RosQtSocket : public QObject

void doConnect();

void init (const std::string &server_hostname);
void open (const std::string &server_hostname, uint16_t port);

void close ();

int64_t read (unsigned char *data, int max_length);

Expand All @@ -58,9 +60,10 @@ private slots:
void readyRead();

private:
QTcpSocket m_socket;
quint16 m_port;
QHostAddress m_address;
QTcpSocket socket_;
bool socket_valid_;
quint16 port_;
QHostAddress address_;
};

#endif
28 changes: 18 additions & 10 deletions src/ros_lib/ros/node_handle.h
Original file line number Diff line number Diff line change
Expand Up @@ -121,14 +121,15 @@ class NodeHandle : public NodeHandleBase_
uint32_t OUTPUT_SIZE;

/*
* Setup Functions
*/
* Setup Functions
*/
public:
NodeHandle(uint32_t input_size=10000, uint32_t output_size=10000, QObject *parent=0) :
NodeHandleBase_(parent),
INPUT_SIZE(input_size),
OUTPUT_SIZE(output_size),
configured_(false)
configured_(false),
isActive_(false)
{
message_in.resize(INPUT_SIZE);
message_out.resize(OUTPUT_SIZE);
Expand All @@ -149,20 +150,23 @@ class NodeHandle : public NodeHandleBase_
spinOnce();
}

/* Start serial, initialize buffers */
void initNode(){

}

/* Start a named port, which may be network server IP, initialize buffers */
void initNode(const std::string &portName){
hardware_.init(portName);
void open(const std::string &hostName, uint16_t port = 11411){
isActive_ = true;
hardware_.open(hostName, port);
mode_ = 0;
bytes_ = 0;
index_ = 0;
topic_ = 0;
}

void close()
{
isActive_ = false;
configured_ = false;
hardware_.close();
}

protected:
//State machine variables for spinOnce
int mode_;
Expand All @@ -172,6 +176,7 @@ class NodeHandle : public NodeHandleBase_
unsigned int checksum_;

bool configured_;
bool isActive_; // true if we should try to connect

/* used for syncing the time */
uint32_t last_sync_time;
Expand All @@ -187,6 +192,9 @@ class NodeHandle : public NodeHandleBase_
virtual int spinOnce(){
unsigned char buffer[READ_BUFFER_SIZE];

if(!isActive_)
return 0;

/* restart if timed out */
uint32_t c_time = hardware_.time();
if( (c_time - last_sync_receive_time) > (SYNC_SECONDS*2200) ){
Expand Down
2 changes: 1 addition & 1 deletion test/Basic/Basic.pro.user
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0" encoding="UTF-8"?>
<!DOCTYPE QtCreatorProject>
<!-- Written by QtCreator 4.3.1, 2017-10-09T12:44:22. -->
<!-- Written by QtCreator 4.4.1, 2017-10-24T14:20:38. -->
<qtcreator>
<data>
<variable>EnvironmentId</variable>
Expand Down
2 changes: 1 addition & 1 deletion test/Basic/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ Node::Node():
std::string ros_master = "127.0.0.1";

printf ("Connecting to server at %s\n", ros_master.c_str());
nh.initNode (ros_master.c_str());
nh.open (ros_master.c_str());

nh.subscribe (poseSub);
nh.advertise(chatter);
Expand Down

0 comments on commit 4a8bb79

Please sign in to comment.