Skip to content

Commit

Permalink
update basic test
Browse files Browse the repository at this point in the history
  • Loading branch information
1r0b1n0 committed Nov 19, 2017
1 parent ad05699 commit 71bb14a
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 10 deletions.
21 changes: 11 additions & 10 deletions test/Basic/node.cpp
Original file line number Diff line number Diff line change
@@ -1,17 +1,9 @@
#include "node.h"
#include <roscpp_tutorials/TwoInts.h>

void estimated_pose_callback (const geometry_msgs::PoseWithCovarianceStamped & pose)
{
printf ("Received pose %f, %f, %f\n", pose.pose.pose.position.x,
pose.pose.pose.position.y, pose.pose.pose.position.z);

std::cout << "Received pose : " << QJsonDocument(pose.serializeAsJson()).toJson(QJsonDocument::Indented).toStdString() << std::endl;
}

Node::Node():
chatter("chatter"),
poseSub("estimated_pose", &estimated_pose_callback),
poseSub("estimated_pose", std::bind(&Node::estimated_pose_callback, this, std::placeholders::_1)),
serviceClient("/rosout/get_loggers"),
serviceServer("add_two_ints", std::bind(&Node::addTwoInts, this, std::placeholders::_1, std::placeholders::_2))
{
Expand All @@ -29,10 +21,19 @@ Node::Node():

nh.serviceClient(serviceClient);

// not supported by rosserial_server
// not yet supported by rosserial_server
//nh.advertiseService(serviceServer);
}

void Node::estimated_pose_callback (const geometry_msgs::PoseWithCovarianceStamped & pose)
{
printf ("Received pose %f, %f, %f\n", pose.pose.pose.position.x,
pose.pose.pose.position.y, pose.pose.pose.position.z);

std::cout << "Received pose : " << QJsonDocument(pose.serializeAsJson()).toJson(QJsonDocument::Indented).toStdString() << std::endl;
}


void Node::onTimer()
{
static int i=1;
Expand Down
1 change: 1 addition & 0 deletions test/Basic/node.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@ public slots:

private:
void addTwoInts(const roscpp_tutorials::TwoIntsRequest &req, roscpp_tutorials::TwoIntsResponse &res);
void estimated_pose_callback (const geometry_msgs::PoseWithCovarianceStamped & pose);

ros::NodeHandle nh;
QTimer *m_timer;
Expand Down

0 comments on commit 71bb14a

Please sign in to comment.