JointStateToPeis::JointStateToPeis()
{
    int my_peis_id = peiskmt_peisid();
    joint_state_sub_ = nh_.subscribe("jaco/joint_states", 1, &JointStateToPeis::jointStateCB, this);
    current_pose_sub_ = nh_.subscribe("jaco/current_pose", 1, &JointStateToPeis::currentPoseCB, this);

    peiskmt_registerTupleCallback(my_peis_id, "jaco_joint_states.publishing_frequency", this, &JointStateToPeis::jointStatePubFreqCB);
    peiskmt_registerTupleCallback(my_peis_id, "jaco_current_pose.publishing_frequency", this, &JointStateToPeis::currentPosePubFreqCB);

    joint_state_pub_freq_ = boost::shared_ptr<ros::Rate> (new ros::Rate(10.0));
    joint_state_pub_freq_ = boost::shared_ptr<ros::Rate> (new ros::Rate(10.0));

    peiskmt_setStringTuple("jaco_joint_states.publishing_frequency", "10.00");
    peiskmt_setStringTuple("jaco_current_pose.publishing_frequency", "10.00");

    peiskmt_setStringTuple("jaco_joint_states.format", "j0 j1 j2 j3 j4 j5 j6");
    peiskmt_setStringTuple("jaco_current_pose.format", "x y z pitch yaw roll");

    pthread_create(&current_pose_publisher_thread_id_, NULL, &JointStateToPeis::current_pose_publisher_thread, (void *) this);
    pthread_create(&joint_state_publisher_thread_id_, NULL, &JointStateToPeis::joint_state_publisher_thread, (void *) this);

    ROS_INFO("Object created!");

}
Ejemplo n.º 2
0
int main(int argn, char** args, char** env) {
	peiskmt_initialize(&argn, args, env);

//	PeisSubscriberHandle s = peiskmt_subscribe(1, "Simple.Publisher_tuple");
	struct simple p;

	pthread_t id;
	pthread_create(&id, NULL, &valueThread, &p);

	printf("CALL\n");
	//PeisCallbackHandle c;
	peiskmt_registerMetaTupleCallback(1, "simple", &p, &callback);

	int i = 20;
	while(i--) {
		sleep(1);
	}

	printf("NO CALL\n");
	peiskmt_unregisterMetaTupleCallback(1, "simple");

	i = 5;
	while(i--) {
		sleep(1);
	}

	printf("CALL AGAIN\n");
	peiskmt_registerTupleCallback(1, "simple", &p, &callback);

	i = 20;
	while(i--) {
		sleep(1);
	}

	printf("NO CALL AGAIN\n");
//	peiskmt_unsubscribe(s);

    pthread_join(id, NULL);
	
	return 0;
}
Ejemplo n.º 3
0
int main(int argc,char **args)
{	
	char configfilename[MAXLENGTH];
	char logfilename[MAXLENGTH];
	FILE* logfile;
	int skipHeader = 0;
	char tuplename[MAXLENGTH];
	int isRunning;
	int element_ready;
	PeisTuple* mytuple;	
	int i;
	int ID, len;
	char* value;
	time_t now;
    struct tm ts;
  	char date[MAXLENGTH];
	float kernel_time;
  
	// handlers
  	PeisSubscriberHandle subHandler[MAXKEYS];
	PeisCallbackHandle callHandler[MAXKEYS];
	  	
	// init isRunning
	isRunning = 1;
	// init the semaphore
	pthread_mutex_init(&tuple_processing, NULL);
	// init the tuple list
	initializeList(&tuples);
	
	// initial check for arguments
  	memcpy(configfilename, CONFIGFILE, strlen(CONFIGFILE)+1);
  	memcpy(logfilename, LOGFILE, strlen(CONFIGFILE)+1);

	for ( i = 0; i < argc; i++ )
    {
		if (strcmp(args[i],"--help") == 0) { printUsage(stderr,argc,args); }
		if (strcmp(args[i],"--conf") == 0) { memcpy(configfilename, args[i+1], strlen(args[i+1])+1); }
		if (strcmp(args[i],"--log") == 0)  { memcpy(logfilename, args[i+1], strlen(args[i+1])+1); }
		if (strcmp(args[i],"--skip") == 0) { skipHeader = 1; }
	}

  	// instantiate & initialize the PEIS component
	peiskmt_initialize(&argc, args);

	// prepare the header of the log file
  	// time: "ddd yyyy-mm-dd hh:mm:ss zzz"
 	time(&now);
  	ts = *localtime(&now);
  	strftime(date, sizeof(date), "%a %Y-%m-%d %H:%M:%S %Z", &ts);
  	kernel_time = peiskmt_gettimef();

  	// Printing the header for the log file
  	if (skipHeader == 0)
	{
        if( !(logfile = fopen(logfilename, "w") ) )
        {
            printf("Error opening the log file %s \n", logfilename);
            isRunning = 0;
        }
        ID = peiskmt_peisid();
        PeisTuple* kernelTuple = peiskmt_getTuple(ID,"kernel.version",PEISK_KEEP_OLD|PEISK_NON_BLOCKING);
        fprintf(logfile, "; Kernel version %s\n", kernelTuple->data);
        fprintf(logfile, "; peislogger version 1.0\n");
        fprintf(logfile, "; starting at %f kernel time, %s\n", kernel_time, date);
        fprintf(logfile, "%f\n", kernel_time);
        fprintf(logfile, "; structure of recorded data:\n");
        fprintf(logfile, "; kernel_ts,write_ts,user_ts,expire_ts,owner,creator,keyDepth,keys,datalenght,data\n");
        fclose(logfile);
	}

  	// Reading the keys of the tuples to subscribe
  	if (!readConfiguration(configfilename))
    {
		printf("Problem reading from configuration file %s \n", configfilename);
		isRunning = 0;
	}
	
  	// Subscribe to all the keys specified in the configuration file and attach a callback
  	for( i = 0 ; i < keyscounter ; i++)
    {
        printf("Subscribing to tuple: \"%s\" ", keys[i]);
        printf("...");
        subHandler[i] = peiskmt_subscribe(-1, keys[i]);
        callHandler[i] = peiskmt_registerTupleCallback(-1, keys[i], NULL, (void*)eventCallback);
        printf("DONE \n");
  	}
 	
  	while( isRunning && peiskmt_isRunning() )
    { 
        // get the tuple to write
  		// not very elegant, but this way I can use the semaphores
		pthread_mutex_lock(&tuple_processing);
  		element_ready = isNotEmpty(&tuples);
		pthread_mutex_unlock(&tuple_processing);

		if(element_ready)
        {
			pthread_mutex_lock(&tuple_processing);
			mytuple = getAndDeleteFirstElement(&tuples);
			pthread_mutex_unlock(&tuple_processing);
			
			peiskmt_printTuple(mytuple);
			printf("\n");
            if ( !(logfile = fopen(logfilename, "a") ) )
            {
				printf("Error appending to logfile file %s \n", logfilename);
				exit(0);
			}
            peiskmt_getTupleName(mytuple, tuplename, sizeof(tuplename));
            fprintf(logfile, "%f %d.%d %d.%d %d.%d %d %d %d %d %d %s %d %s\n", 
			peiskmt_gettimef(), mytuple->ts_write[0], mytuple->ts_write[1], 
			mytuple->ts_user[0], mytuple->ts_user[1], mytuple->ts_expire[0], mytuple->ts_expire[1],
			mytuple->owner, mytuple->creator, mytuple->alloclen, mytuple->isNew, mytuple->keyDepth, 
			tuplename, strlen(mytuple->data)+1, (char*)mytuple->data);
    		fclose(logfile);
		}		
	    usleep(10000);
  	}

	// unsubscribe
	for( i = 0 ; i < keyscounter ; i++)
    {
        peiskmt_unsubscribe(subHandler[i]);
		peiskmt_unregisterTupleCallback(callHandler[i]);
	}

	// free the memory of both the queue and the variables
	peiskmt_freeTuple(mytuple);
	emptyQueue(&tuples);
	pthread_mutex_destroy(&tuple_processing);
  	
	peiskmt_shutdown();
}