void WidgetsInterfaceKit::OnWtRatiometricStateChanged(Wt::WCheckBox* checkbox)
{
	bool ratiometric = checkbox->isChecked();
	CPhidgetInterfaceKit_setRatiometric(m_phidget->GetNativeHandle(), ratiometric ? PTRUE : PFALSE);
	::GetApplicationManager()->OnWtRatiometricChanged(GetApplication(), GetSerial(), ratiometric);

	UpdateSensorFunctionDropdowns(ratiometric);

	GetApplication()->triggerUpdate();
}
int interfacekit_simple()
{
	int result, numSensors, i;
	const char *err;

	//Declare an InterfaceKit handle
	CPhidgetInterfaceKitHandle ifKit = 0;

	//create the InterfaceKit object
	CPhidgetInterfaceKit_create(&ifKit);

	//Set the handlers to be run when the device is plugged in or opened from software, unplugged or closed from software, or generates an error.
	CPhidget_set_OnAttach_Handler((CPhidgetHandle)ifKit, AttachHandler, NULL);
	CPhidget_set_OnDetach_Handler((CPhidgetHandle)ifKit, DetachHandler, NULL);
	CPhidget_set_OnError_Handler((CPhidgetHandle)ifKit, ErrorHandler, NULL);

	//Registers a callback that will run if an input changes.
	//Requires the handle for the Phidget, the function that will be called, and an arbitrary pointer that will be supplied to the callback function (may be NULL).
	CPhidgetInterfaceKit_set_OnInputChange_Handler (ifKit, InputChangeHandler, NULL);

	//Registers a callback that will run if the sensor value changes by more than the OnSensorChange trig-ger.
	//Requires the handle for the IntefaceKit, the function that will be called, and an arbitrary pointer that will be supplied to the callback function (may be NULL).
	CPhidgetInterfaceKit_set_OnSensorChange_Handler (ifKit, SensorChangeHandler, NULL);

	//Registers a callback that will run if an output changes.
	//Requires the handle for the Phidget, the function that will be called, and an arbitrary pointer that will be supplied to the callback function (may be NULL).
	CPhidgetInterfaceKit_set_OnOutputChange_Handler (ifKit, OutputChangeHandler, NULL);

	//open the interfacekit for device connections
	CPhidget_open((CPhidgetHandle)ifKit, -1);

	//get the program to wait for an interface kit device to be attached
	printf("Waiting for interface kit to be attached....");
	if((result = CPhidget_waitForAttachment((CPhidgetHandle)ifKit, 10000)))
	{
		CPhidget_getErrorDescription(result, &err);
		printf("Problem waiting for attachment: %s\n", err);
		return 0;
	}

	//Display the properties of the attached interface kit device
	display_properties(ifKit);

	//read interface kit event data
	printf("Reading.....\n");

	//keep displaying interface kit data until user input is read
	printf("Press any key to go to next step\n");
	getchar();

	printf("Modifying sensor sensitivity triggers....\n");

	//get the number of sensors available
	CPhidgetInterfaceKit_getSensorCount(ifKit, &numSensors);

	//Change the sensitivity trigger of the sensors
	for(i = 0; i < numSensors; i++)
	{
		CPhidgetInterfaceKit_setSensorChangeTrigger(ifKit, i, 100);  //we'll just use 10 for fun
	}

	//read interface kit event data
	printf("Reading.....\n");

	//keep displaying interface kit data until user input is read
	printf("Press any key to go to next step\n");
	getchar();

	printf("Toggling Ratiometric....\n");

	CPhidgetInterfaceKit_setRatiometric(ifKit, 0);

	//read interface kit event data
	printf("Reading.....\n");

	//keep displaying interface kit data until user input is read
	printf("Press any key to end\n");
	getchar();

	//since user input has been read, this is a signal to terminate the program so we will close the phidget and delete the object we created
	printf("Closing...\n");
	CPhidget_close((CPhidgetHandle)ifKit);
	CPhidget_delete((CPhidgetHandle)ifKit);

	//all done, exit
	return 0;
}
Beispiel #3
0
int interfacekit_simple()
// initialize the phidget interface kit board and phidget spatial (imu)
{
	int result, num_analog_inputs, num_digital_inputs;
	const char *err;
	ros::NodeHandle n;

	//create the InterfaceKit object
	CPhidgetInterfaceKit_create(&ifKit);

	//Set the handlers to be run when the device is plugged in or opened from software, unplugged or closed from software, or generates an error.
	CPhidget_set_OnError_Handler((CPhidgetHandle)ifKit, ErrorHandler, NULL);
	CPhidgetInterfaceKit_set_OnInputChange_Handler (ifKit, DigitalInputHandler, NULL);
	CPhidgetInterfaceKit_set_OnSensorChange_Handler (ifKit, AnalogInputHandler, NULL);


	//open the interfacekit and spatial for device connections
	CPhidget_open((CPhidgetHandle)ifKit, -1);
	

	CPhidgetInterfaceKit_getInputCount(ifKit, &num_digital_inputs);
	CPhidgetInterfaceKit_getSensorCount(ifKit, &num_analog_inputs);


	printf("Waiting for interface kit to be attached....");
	if((result = CPhidget_waitForAttachment((CPhidgetHandle)ifKit, 1000)))
	{
		CPhidget_getErrorDescription(result, &err);
		ROS_ERROR("Phidget IK: Problem waiting for attachment: %s\n", err);
		interfaceKitError = 1;
	}
	else
	{
        	irData_pub = n.advertise<corobot_msgs::SensorMsg>("infrared_data", 100);
        	powerdata_pub = n.advertise<corobot_msgs::PowerMsg>("power_data", 100);
        	bumper_pub = n.advertise<corobot_msgs::SensorMsg>("bumper_data", 100);
		// sensors connected to the phidget interface kit other than bumpers, voltage sensor, ir sensor and sonars. 
        	other_pub = n.advertise<corobot_msgs::SensorMsg>("sensor_data", 100); 
	}	
	

	//Initialize the phidget spatial board, if any
	if (imu)
	{
		CPhidgetSpatial_create(&spatial);
		CPhidget_set_OnError_Handler((CPhidgetHandle)spatial, ErrorHandler, NULL);
		CPhidgetSpatial_set_OnSpatialData_Handler(spatial, SpatialDataHandler, NULL);
		CPhidget_open((CPhidgetHandle)spatial, -1);

		// attach the devices
		printf("Waiting for spatial to be attached.... \n");
		if((result = CPhidget_waitForAttachment((CPhidgetHandle)spatial, 1000)))
		{
			CPhidget_getErrorDescription(result, &err);
			ROS_ERROR("Phidget Spatial: Problem waiting for attachment: %s\n", err);
			spatialError = 1;
		}
		else
		{
			imu_pub = n.advertise<sensor_msgs::Imu>("imu_data",100);
			mag_pub = n.advertise<sensor_msgs::MagneticField>("magnetic_data",100);
      calibrate_gyroscope_service = n.advertiseService("calibrate_gyroscope",calibrate_gyroscope);
		}

		CPhidgetSpatial_setDataRate(spatial, 4);
	}

	CPhidgetInterfaceKit_setRatiometric(ifKit, 0);

	//Initialize the sonars, if any are present
	if(sonarsPresent)
	{
		CPhidgetInterfaceKit_setOutputState(ifKit, bwOutput, 1);
		CPhidgetInterfaceKit_setOutputState(ifKit, strobeOutput, 0);
		// sleep for 250ms
		ros::Duration(0.250).sleep(); 
		CPhidgetInterfaceKit_setOutputState(ifKit, strobeOutput, 1);
		// sleep for 2ms
		ros::Duration(0.002).sleep(); 
		CPhidgetInterfaceKit_setOutputState(ifKit, strobeOutput, 0);
		// sleep for 150ms
		ros::Duration(0.150).sleep(); 

		sonar_pub = n.advertise<corobot_msgs::SensorMsg>("sonar_data", 100);
	}
	return 0;
}
int interfacekit_simple()
{
	int result, num_analog_inputs, num_digital_inputs;
	const char *err;

	//create the InterfaceKit object
	CPhidgetInterfaceKit_create(&ifKit);

	//Set the handlers to be run when the device is plugged in or opened from software, unplugged or closed from software, or generates an error.

	CPhidget_set_OnDetach_Handler((CPhidgetHandle)ifKit, DetachHandler, NULL);
	CPhidget_set_OnError_Handler((CPhidgetHandle)ifKit, ErrorHandler, NULL);
           
	CPhidgetInterfaceKit_set_OnInputChange_Handler (ifKit, InputChangeHandler, NULL);

	CPhidgetInterfaceKit_set_OnSensorChange_Handler (ifKit, SensorChangeHandler, NULL);

	CPhidgetInterfaceKit_set_OnOutputChange_Handler (ifKit, OutputChangeHandler, NULL);

	//For phidget spatial
	//CPhidgetSpatialHandle spatial = 0;
	CPhidgetSpatial_create(&spatial);
	CPhidget_set_OnAttach_Handler((CPhidgetHandle)spatial, AttachHandler, NULL);
	CPhidget_set_OnDetach_Handler((CPhidgetHandle)spatial, DetachHandler, NULL);
	CPhidget_set_OnError_Handler((CPhidgetHandle)spatial, ErrorHandler, NULL);
	CPhidgetSpatial_set_OnSpatialData_Handler(spatial, SpatialDataHandler, NULL);


	//open the interfacekit for device connections
	CPhidget_open((CPhidgetHandle)ifKit, -1);


	CPhidget_open((CPhidgetHandle)spatial, -1);


	CPhidgetInterfaceKit_getInputCount(ifKit, &num_digital_inputs);
	CPhidgetInterfaceKit_getSensorCount(ifKit, &num_analog_inputs);


	printf("Waiting for spatial to be attached.... \n");
	if((result = CPhidget_waitForAttachment((CPhidgetHandle)spatial, 1000)))
	{
		CPhidget_getErrorDescription(result, &err);
		ROS_ERROR("Phidget Spatial: Problem waiting for attachment: %s\n", err);
		spatialError = 1;
	}

	printf("Waiting for interface kit to be attached....");
	if((result = CPhidget_waitForAttachment((CPhidgetHandle)ifKit, 1000)))
	{
		CPhidget_getErrorDescription(result, &err);
		ROS_ERROR("Phidget IK: Problem waiting for attachment: %s\n", err);
		phidget888_connected = false;
		interfaceKitError = 1;
	}

	phidget888_connected = true;
	
	CPhidgetInterfaceKit_setRatiometric(ifKit, 0);//

	CPhidgetSpatial_setDataRate(spatial, 16);	

	 CPhidgetEncoder_create(&m_leftEncoder);
         CPhidget_set_OnAttach_Handler((CPhidgetHandle) m_leftEncoder,LeftEncoderAttach, NULL);
         CPhidget_open((CPhidgetHandle) m_leftEncoder, -1);
        
	if (m_encoder1Seen && m_encoder2Seen)
	    phidget_encoder_connected = true;
	else phidget_encoder_connected = false;

	//Initialize the sonars, if any are present
	if(sonarsPresent)
	{
		CPhidgetInterfaceKit_setOutputState(ifKit, bwOutput, 1);
		CPhidgetInterfaceKit_setOutputState(ifKit, strobeOutput, 0);
		ros::Duration(0.250).sleep(); // sleep for 250ms
		CPhidgetInterfaceKit_setOutputState(ifKit, strobeOutput, 1);
		ros::Duration(0.002).sleep(); // sleep for 2ms
		CPhidgetInterfaceKit_setOutputState(ifKit, strobeOutput, 0);
		ros::Duration(0.150).sleep(); // sleep for 150ms
	}
	return 0;
}