Introduce Trick ROS publish/subscribe examples.

Introducing a pubish and subscribe example sim.  The publisher includes
a ROS msg file that is processed by ROS into a header file.

refs #190
This commit is contained in:
Alex Lin 2016-02-26 09:39:42 -06:00
parent 5a7cd1839b
commit 4c471eb32d
14 changed files with 472 additions and 0 deletions

View File

@ -0,0 +1,9 @@
def main():
trick.real_time_enable()
trick.exec_set_software_frame(0.5)
if __name__ == "__main__":
main()

View File

@ -0,0 +1,20 @@
#include "sim_objects/default_trick_sys.sm"
##include "ros_comm/ros_framework.hh"
##include "ros_comm/ros_publish.hh"
class RosPublishSimObject : public Trick::SimObject {
public:
RosFramework rf ;
RosPublish rp ;
RosPublishSimObject() : rf("talker") , rp() {
("initialization") rp.init() ;
(0.5, "scheduled") rp.publish() ;
("shutdown") rf.shutdown() ;
}
} ;
RosPublishSimObject rp_so ;

View File

@ -0,0 +1,20 @@
ROS_HOME = /opt/ros/jade
TRICK_ICG_EXCLUDE += :${ROS_HOME}
TRICK_CFLAGS += -I../models -I${ROS_HOME}/include
TRICK_CXXFLAGS += -I../models -I${ROS_HOME}/include -Wno-shadow -Wno-unused-parameter
TRICK_EXEC_LINK_LIBS += -L${ROS_HOME}/lib -lroscpp -lrosconsole -lroscpp_serialization
$(MODEL_cpp_OBJ) : | ../models/ros_comm/Num.h
MESSAGE_FILES = ../models/ros_comm/Num.h
${MESSAGE_FILES} : %.h : %.msg
cd ${<D} && ${ROS_HOME}/lib/gencpp/gen_cpp.py ${<F} -Itrick_msgs:. -Istd_msgs:${ROS_HOME}/share/std_msgs/cmake/../msg -p trick_msgs -o . -e /opt/ros/jade/share/gencpp
clean: clean_msg_headers
clean_msg_headers:
rm -f ${HOME}/trick_models/ros_comm/Num.h

View File

@ -0,0 +1,11 @@
def main():
trick.real_time_enable()
trick.itimer_enable()
trick.exec_set_software_frame(0.5)
trick.exec_set_thread_process_type(1, trick.PROCESS_TYPE_ASYNC_CHILD)
if __name__ == "__main__":
main()

View File

@ -0,0 +1,20 @@
#include "sim_objects/default_trick_sys.sm"
##include "ros_comm/ros_framework.hh"
##include "ros_comm/ros_subscribe.hh"
class RosSubscribeSimObject : public Trick::SimObject {
public:
RosFramework rf ;
RosSubscribe rp ;
RosSubscribeSimObject() : rf("trick_listener") , rp() {
("initialization") rp.init() ;
C1 (0.5, "scheduled") rp.process() ;
("shutdown") rf.shutdown() ;
}
} ;
RosSubscribeSimObject rs_so ;

View File

@ -0,0 +1,8 @@
ROS_HOME = /opt/ros/jade
TRICK_ICG_EXCLUDE += :${ROS_HOME}
TRICK_CFLAGS += -I../models -I${ROS_HOME}/include
TRICK_CXXFLAGS += -I../models -I${ROS_HOME}/include -Wno-shadow -Wno-unused-parameter
TRICK_EXEC_LINK_LIBS += -L${ROS_HOME}/lib -lroscpp -lrosconsole -lroscpp_serialization

View File

@ -0,0 +1,239 @@
// Generated by gencpp from file trick_msgs/Num.msg
// DO NOT EDIT!
#ifndef TRICK_MSGS_MESSAGE_NUM_H
#define TRICK_MSGS_MESSAGE_NUM_H
#include <string>
#include <vector>
#include <map>
#include <ros/types.h>
#include <ros/serialization.h>
#include <ros/builtin_message_traits.h>
#include <ros/message_operations.h>
namespace trick_msgs
{
template <class ContainerAllocator>
struct Num_
{
typedef Num_<ContainerAllocator> Type;
Num_()
: first_name()
, last_name()
, date()
, points(0)
, rebounds(0)
, blocks(0)
, assists(0) {
}
Num_(const ContainerAllocator& _alloc)
: first_name(_alloc)
, last_name(_alloc)
, date(_alloc)
, points(0)
, rebounds(0)
, blocks(0)
, assists(0) {
}
typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _first_name_type;
_first_name_type first_name;
typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _last_name_type;
_last_name_type last_name;
typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _date_type;
_date_type date;
typedef uint8_t _points_type;
_points_type points;
typedef uint32_t _rebounds_type;
_rebounds_type rebounds;
typedef uint32_t _blocks_type;
_blocks_type blocks;
typedef uint32_t _assists_type;
_assists_type assists;
typedef boost::shared_ptr< ::trick_msgs::Num_<ContainerAllocator> > Ptr;
typedef boost::shared_ptr< ::trick_msgs::Num_<ContainerAllocator> const> ConstPtr;
}; // struct Num_
typedef ::trick_msgs::Num_<std::allocator<void> > Num;
typedef boost::shared_ptr< ::trick_msgs::Num > NumPtr;
typedef boost::shared_ptr< ::trick_msgs::Num const> NumConstPtr;
// constants requiring out of line definition
template<typename ContainerAllocator>
std::ostream& operator<<(std::ostream& s, const ::trick_msgs::Num_<ContainerAllocator> & v)
{
ros::message_operations::Printer< ::trick_msgs::Num_<ContainerAllocator> >::stream(s, "", v);
return s;
}
} // namespace trick_msgs
namespace ros
{
namespace message_traits
{
// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False}
// {'trick_msgs': ['.'], 'std_msgs': ['/opt/ros/jade/share/std_msgs/cmake/../msg']}
// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types']
template <class ContainerAllocator>
struct IsFixedSize< ::trick_msgs::Num_<ContainerAllocator> >
: FalseType
{ };
template <class ContainerAllocator>
struct IsFixedSize< ::trick_msgs::Num_<ContainerAllocator> const>
: FalseType
{ };
template <class ContainerAllocator>
struct IsMessage< ::trick_msgs::Num_<ContainerAllocator> >
: TrueType
{ };
template <class ContainerAllocator>
struct IsMessage< ::trick_msgs::Num_<ContainerAllocator> const>
: TrueType
{ };
template <class ContainerAllocator>
struct HasHeader< ::trick_msgs::Num_<ContainerAllocator> >
: FalseType
{ };
template <class ContainerAllocator>
struct HasHeader< ::trick_msgs::Num_<ContainerAllocator> const>
: FalseType
{ };
template<class ContainerAllocator>
struct MD5Sum< ::trick_msgs::Num_<ContainerAllocator> >
{
static const char* value()
{
return "345b622c1a8704503c97d4d3be56b05d";
}
static const char* value(const ::trick_msgs::Num_<ContainerAllocator>&) { return value(); }
static const uint64_t static_value1 = 0x345b622c1a870450ULL;
static const uint64_t static_value2 = 0x3c97d4d3be56b05dULL;
};
template<class ContainerAllocator>
struct DataType< ::trick_msgs::Num_<ContainerAllocator> >
{
static const char* value()
{
return "trick_msgs/Num";
}
static const char* value(const ::trick_msgs::Num_<ContainerAllocator>&) { return value(); }
};
template<class ContainerAllocator>
struct Definition< ::trick_msgs::Num_<ContainerAllocator> >
{
static const char* value()
{
return "string first_name\n\
string last_name\n\
string date\n\
uint8 points\n\
uint32 rebounds\n\
uint32 blocks\n\
uint32 assists\n\
";
}
static const char* value(const ::trick_msgs::Num_<ContainerAllocator>&) { return value(); }
};
} // namespace message_traits
} // namespace ros
namespace ros
{
namespace serialization
{
template<class ContainerAllocator> struct Serializer< ::trick_msgs::Num_<ContainerAllocator> >
{
template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
{
stream.next(m.first_name);
stream.next(m.last_name);
stream.next(m.date);
stream.next(m.points);
stream.next(m.rebounds);
stream.next(m.blocks);
stream.next(m.assists);
}
ROS_DECLARE_ALLINONE_SERIALIZER;
}; // struct Num_
} // namespace serialization
} // namespace ros
namespace ros
{
namespace message_operations
{
template<class ContainerAllocator>
struct Printer< ::trick_msgs::Num_<ContainerAllocator> >
{
template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::trick_msgs::Num_<ContainerAllocator>& v)
{
s << indent << "first_name: ";
Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.first_name);
s << indent << "last_name: ";
Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.last_name);
s << indent << "date: ";
Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.date);
s << indent << "points: ";
Printer<uint8_t>::stream(s, indent + " ", v.points);
s << indent << "rebounds: ";
Printer<uint32_t>::stream(s, indent + " ", v.rebounds);
s << indent << "blocks: ";
Printer<uint32_t>::stream(s, indent + " ", v.blocks);
s << indent << "assists: ";
Printer<uint32_t>::stream(s, indent + " ", v.assists);
}
};
} // namespace message_operations
} // namespace ros
#endif // TRICK_MSGS_MESSAGE_NUM_H

View File

@ -0,0 +1,7 @@
string first_name
string last_name
string date
uint8 points
uint32 rebounds
uint32 blocks
uint32 assists

View File

@ -0,0 +1,18 @@
#include "ros/ros.h"
#include "trick/command_line_protos.h"
#include "ros_framework.hh"
RosFramework::RosFramework(std::string app_name) {
int argc = command_line_args_get_argc() ;
char **argv = command_line_args_get_argv() ;
ros::init(argc, argv, app_name.c_str(), ros::init_options::NoSigintHandler) ;
}
RosFramework::~RosFramework() {}
int RosFramework::shutdown() {
ros::shutdown() ;
return 0 ;
}

View File

@ -0,0 +1,19 @@
/*
PURPOSE: (To be)
LIBRARY_DEPENDENCIES: (ros_framework.cpp)
*/
#ifndef ROS_FRAMEWORK_HH
#define ROS_FRAMEWORK_HH
#include <string>
class RosFramework {
public:
RosFramework(std::string app_name) ;
virtual ~RosFramework() ;
virtual int shutdown() ;
} ;
#endif

View File

@ -0,0 +1,34 @@
#include "std_msgs/String.h"
#include "trick/exec_proto.h"
#include "ros_publish.hh"
#include "Num.h"
RosPublish::RosPublish() : count(0) {}
int RosPublish::init() {
msg_pub = n.advertise<trick_msgs::Num>("num_chatter", 1000) ;
return 0 ;
}
int RosPublish::publish() {
if ( ros::ok() ) {
trick_msgs::Num tn ;
tn.first_name = "Hakeem" ;
tn.last_name = "Olajuwon" ;
tn.date = "March 29, 1990" ;
tn.points = 18 ;
tn.rebounds = 16 ;
tn.blocks = 11 ;
tn.assists = 10 ;
std::cout << tn << std::endl ;
msg_pub.publish(tn) ;
ros::spinOnce() ;
} else {
exec_terminate(__FILE__, "ros not ok") ;
}
return 0 ;
}

View File

@ -0,0 +1,24 @@
/*
PURPOSE: (To be)
LIBRARY_DEPENDENCIES: (ros_publish.cpp)
*/
#ifndef ROS_PUBLISH_HH
#define ROS_PUBLISH_HH
#include "ros/ros.h"
class RosPublish {
public:
ros::NodeHandle n ; // ** ros nodehandle
ros::Publisher msg_pub ; // ** ros publisher
int count ;
RosPublish() ;
int init() ;
int publish() ;
} ;
#endif

View File

@ -0,0 +1,21 @@
#include "std_msgs/String.h"
#include "ros_subscribe.hh"
#include "Num.h"
void numchatterCallback(const trick_msgs::Num::ConstPtr& msg) {
std::cout << *msg << std::endl ;
}
RosSubscribe::RosSubscribe() {}
int RosSubscribe::init() {
sub = n.subscribe("num_chatter", 1000, numchatterCallback) ;
return 0 ;
}
int RosSubscribe::process() {
ros::spin() ;
return 0 ;
}

View File

@ -0,0 +1,22 @@
/*
PURPOSE: (To be)
LIBRARY_DEPENDENCIES: (ros_subscribe.cpp)
*/
#ifndef ROS_SUBSCRIBE_HH
#define ROS_SUBSCRIBE_HH
#include "ros/ros.h"
class RosSubscribe {
public:
ros::NodeHandle n ; // ** ros nodehandle
ros::Subscriber sub ; // ** ros subscriber
RosSubscribe() ;
int init() ;
int process() ;
} ;
#endif