diff --git a/CMakeLists.txt b/CMakeLists.txt index 2dda4a23f1e727a47ff75b291f66b1ed6c9d4edc..51cf1dbba6c7adb536aba2cc648214e172820e8e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,7 +1,17 @@ cmake_minimum_required(VERSION 3.0.2) project(turtlesim_xl) -find_package(catkin REQUIRED COMPONENTS geometry_msgs message_generation rosconsole roscpp roscpp_serialization roslib rostime std_msgs std_srvs) +find_package(catkin REQUIRED COMPONENTS + geometry_msgs + message_generation + rosconsole + roscpp + roscpp_serialization + roslib + rostime + std_msgs + std_srvs +) find_package(Qt5Widgets REQUIRED) find_package(Boost REQUIRED COMPONENTS thread) @@ -10,13 +20,15 @@ include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS}) link_directories(${catkin_LIBRARY_DIRS}) add_message_files(DIRECTORY msg FILES - Color.msg Pose.msg) + Color.msg Pose.msg img.msg) + add_service_files(DIRECTORY srv FILES Kill.srv SetPen.srv Spawn.srv TeleportAbsolute.srv TeleportRelative.srv) + generate_messages(DEPENDENCIES geometry_msgs std_msgs std_srvs) catkin_package(CATKIN_DEPENDS geometry_msgs message_runtime std_msgs std_srvs) diff --git a/msg/img.msg b/msg/img.msg new file mode 100644 index 0000000000000000000000000000000000000000..02795b4e27ee45676630dc3e25b1395ac0bb5ca6 --- /dev/null +++ b/msg/img.msg @@ -0,0 +1,4 @@ +int64 x +int64 y +# uint64[] img +string imgPath \ No newline at end of file diff --git a/src/turtlesim_xl.cpp b/src/turtlesim_xl.cpp index 14f1623f77e5f5e808608dce738e68ecdd020dae..584f20df5e2dafdf69ec3f7355ac5a97197097c3 100644 --- a/src/turtlesim_xl.cpp +++ b/src/turtlesim_xl.cpp @@ -32,9 +32,13 @@ #include <ros/ros.h> #include "turtlesim/turtle_frame.h" +#include <turtlesim_xl/img.h> class TurtleApp : public QApplication { + turtlesim_xl::img shapeData; + ros::Subscriber shapeSub; + turtlesim::TurtleFrame* frame; public: ros::NodeHandlePtr nh_; @@ -42,18 +46,32 @@ public: : QApplication(argc, argv) { ros::init(argc, argv, "turtlesim", ros::init_options::NoSigintHandler); + ros::NodeHandle n; nh_.reset(new ros::NodeHandle); + // turtlesim::TurtleFrame fr; + // frame = &fr; + frame = new turtlesim::TurtleFrame(); + + shapeSub = n.subscribe("/shapeData", 10, &TurtleApp::updateShape, this); } int exec(std::string shape = "rectangle") { - turtlesim::TurtleFrame frame; - frame.setShape(shape); - frame.drawShape(); - frame.show(); + frame->setShape(shape); + ROS_INFO("Offset before calling draw: x = %d; y = %d", shapeData.x, shapeData.y); + frame->drawShape(); + frame->show(); return QApplication::exec(); } + +private: + void updateShape(turtlesim_xl::img data) { + shapeData = data; + ROS_INFO("NEW SHAPE DATA SAVED"); + frame->setShape("triangle"); + frame->drawShape(); + } }; int main(int argc, char** argv)