#include <ROSComm.h>
ROSTopicManager::ROSTopicManager | ( | VisFinder * | s_visFinder, |
SignatureDB * | s_sigDb | ||
) |
Definition at line 454 of file ROSComm.cpp.
Definition at line 460 of file ROSComm.cpp.
void ROSTopicManager::CloseROSTopic | ( | std::string | name | ) |
Definition at line 468 of file ROSComm.cpp.
void ROSTopicManager::FeedbackCallBack | ( | vision_msgs::cop_feedback::ConstPtr | feedback | ) |
Definition at line 813 of file ROSComm.cpp.
void ROSTopicManager::Listen | ( | std::string | name, |
volatile bool & | g_stopall, | ||
ros::NodeHandle * | node | ||
) |
Now we subscribe using the normal method, to demonstrate the difference.
Definition at line 844 of file ROSComm.cpp.
bool ROSTopicManager::ListenCallBack | ( | vision_srvs::cop_call::Request & | request, |
vision_srvs::cop_call::Response & | answer | ||
) |
Definition at line 492 of file ROSComm.cpp.
bool ROSTopicManager::ListProgramCallBack | ( | vision_srvs::cop_get_methods_list::Request & | msg, |
vision_srvs::cop_get_methods_list::Response & | answer | ||
) |
#define ALGORITHMTYPE_LOCATE 0x000 #define ALGORITHMTYPE_TRACK 0x010 #define ALGORITHMTYPE_REFINE 0x100 #define ALGORITHMTYPE_2OBJS 0x200 #define ALGORITHMTYPE_RPOVE 0x400 #define ALGORITHMTYPE_STARTATTEND 0x1000
Definition at line 776 of file ROSComm.cpp.
void ROSTopicManager::NewSignatureCallBack | ( | std_msgs::String::ConstPtr | xmlFilename | ) |
Definition at line 705 of file ROSComm.cpp.
bool ROSTopicManager::OpenCommOnROSTopic | ( | std::string | st | ) |
Definition at line 897 of file ROSComm.cpp.
bool ROSTopicManager::SaveCallBack | ( | vision_srvs::cop_save::Request & | msg, |
vision_srvs::cop_save::Response & | answer | ||
) |
Definition at line 650 of file ROSComm.cpp.
void ROSTopicManager::StatusThread | ( | ) |
Definition at line 904 of file ROSComm.cpp.
void ROSTopicManager::Subscriber | ( | const ros::SingleSubscriberPublisher & | subs | ) |
Definition at line 473 of file ROSComm.cpp.
std::map<std::string, ros::Publisher*> cop::ROSTopicManager::m_openTopics |
std::map<std::string, std::vector<std::string> > cop::ROSTopicManager::m_subscriberPerTopics |