Skip to content

Commit

Permalink
[Refactor] Move the custom type for error code to the virtual class
Browse files Browse the repository at this point in the history
To use the custom data type for error code in both ROS1/ROS2 publishers,
this patch moves it to the virtual class.

Signed-off-by: Wook Song <[email protected]>
  • Loading branch information
wooksong committed Oct 22, 2020
1 parent ad70068 commit 3e09d4a
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 9 deletions.
5 changes: 5 additions & 0 deletions include/nns_ros_publisher.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,11 @@
#include <nnstreamer/tensor_typedef.h>
#include <nnstreamer/nnstreamer_plugin_api.h>

typedef enum _err_code {
ROS1_UNDEFINED_ROS_MASTER_URI,
ROS1_FAILED_TO_CONNECT_ROSCORE,
} err_code;

#ifdef __cplusplus
#include <string>

Expand Down
13 changes: 4 additions & 9 deletions ros/node/nns_roscpp_publisher.cc
Original file line number Diff line number Diff line change
Expand Up @@ -27,11 +27,6 @@

const char BASE_NODE_NAME[] = "tensor_ros_sink";

typedef enum _err_code {
UNDEFINED_ROS_MASTER_URI,
FAILED_TO_CONNECT_ROSCORE,
} err_code;

class NnsRosCppPublisher
: public NnsRosPublisher<std_msgs::MultiArrayLayout, guint>
{
Expand Down Expand Up @@ -71,11 +66,11 @@ NnsRosCppPublisher::NnsRosCppPublisher (const char *node_name,
char **dummy_argv = NULL;

if (!is_dummy) {
if (getenv ("ROS_MASTER_URI") == NULL) throw UNDEFINED_ROS_MASTER_URI;
if (getenv ("ROS_MASTER_URI") == NULL) throw ROS1_UNDEFINED_ROS_MASTER_URI;

ros::init (dummy_argc, dummy_argv, this->str_node_name);

if (!ros::master::check ()) throw FAILED_TO_CONNECT_ROSCORE;
if (!ros::master::check ()) throw ROS1_FAILED_TO_CONNECT_ROSCORE;

this->nh_parent = new ros::NodeHandle (BASE_NODE_NAME);
this->nh_child =
Expand Down Expand Up @@ -160,12 +155,12 @@ void *nns_ros_publisher_init (const char *node_name, const char *topic_name,
return new NnsRosCppPublisher (node_name, topic_name, is_dummy);
} catch (const err_code e) {
switch (e) {
case UNDEFINED_ROS_MASTER_URI:
case ROS1_UNDEFINED_ROS_MASTER_URI:
g_critical ("%s: ROS_MASTER_URI is not defined in the environment\n",
NnsRosCppPublisher::getHelperName ());
break;

case FAILED_TO_CONNECT_ROSCORE:
case ROS1_FAILED_TO_CONNECT_ROSCORE:
g_critical (
"%s: failed to connect to master: please make sure roscore is "
"running\n", NnsRosCppPublisher::getHelperName ());
Expand Down

0 comments on commit 3e09d4a

Please sign in to comment.