Exemple #1
0
void read_parameters(int argc, char **argv)
{
  char *dev="";

  carmen_param_t hokuyo_dev =  {"hokuyo", "hokuyo_dev", CARMEN_PARAM_STRING, &dev, 0, NULL};
  strcpy(hokuyo.device_name, dev);
  carmen_param_t hokuyo_params={"hokuyo", "hokuyo_flipped", CARMEN_PARAM_INT, 
     &hokuyo.flipped, 0, NULL};
  carmen_param_install_params(argc, argv, &hokuyo_dev, 1);
  carmen_param_install_params(argc, argv, &hokuyo_params,1);
  strcpy(hokuyo.device_name,dev);
}
static void 
initialize_carmen_parameters(xsens_xyz_handler *xsens_handler, int argc, char **argv)
{
	int num_items;

	carmen_param_t param_list[] = 
	{
		{(char*)"sensor_board_1", (char*)"x",		CARMEN_PARAM_DOUBLE, &xsens_handler->sensor_board_pose.position.x,	0, NULL},
		{(char*)"sensor_board_1", (char*)"y",		CARMEN_PARAM_DOUBLE, &xsens_handler->sensor_board_pose.position.y,	0, NULL},
		{(char*)"sensor_board_1", (char*)"z",		CARMEN_PARAM_DOUBLE, &xsens_handler->sensor_board_pose.position.z,	0, NULL},
		{(char*)"sensor_board_1", (char*)"roll",	CARMEN_PARAM_DOUBLE, &xsens_handler->sensor_board_pose.orientation.roll,0, NULL},
		{(char*)"sensor_board_1", (char*)"pitch",	CARMEN_PARAM_DOUBLE, &xsens_handler->sensor_board_pose.orientation.pitch,0, NULL},
		{(char*)"sensor_board_1", (char*)"yaw",		CARMEN_PARAM_DOUBLE, &xsens_handler->sensor_board_pose.orientation.yaw,	0, NULL},

		{(char*)"xsens", (char*)"x",			CARMEN_PARAM_DOUBLE, &xsens_handler->xsens_pose.position.x,		0, NULL},
		{(char*)"xsens", (char*)"y",			CARMEN_PARAM_DOUBLE, &xsens_handler->xsens_pose.position.y,		0, NULL},
		{(char*)"xsens", (char*)"z",			CARMEN_PARAM_DOUBLE, &xsens_handler->xsens_pose.position.z,		0, NULL},
		{(char*)"xsens", (char*)"roll",			CARMEN_PARAM_DOUBLE, &xsens_handler->xsens_pose.orientation.roll,	0, NULL},
		{(char*)"xsens", (char*)"pitch",		CARMEN_PARAM_DOUBLE, &xsens_handler->xsens_pose.orientation.pitch,	0, NULL},
		{(char*)"xsens", (char*)"yaw",			CARMEN_PARAM_DOUBLE, &xsens_handler->xsens_pose.orientation.yaw,	0, NULL},

		{(char*)"gps_nmea", (char*)"x",			CARMEN_PARAM_DOUBLE, &xsens_handler->gps_pose_in_the_car.position.x,		0, NULL},
		{(char*)"gps_nmea", (char*)"y",			CARMEN_PARAM_DOUBLE, &xsens_handler->gps_pose_in_the_car.position.y,		0, NULL},
		{(char*)"gps_nmea", (char*)"z",			CARMEN_PARAM_DOUBLE, &xsens_handler->gps_pose_in_the_car.position.z,		0, NULL},
		{(char*)"gps_nmea", (char*)"roll",		CARMEN_PARAM_DOUBLE, &xsens_handler->gps_pose_in_the_car.orientation.roll,		0, NULL},
		{(char*)"gps_nmea", (char*)"pitch",		CARMEN_PARAM_DOUBLE, &xsens_handler->gps_pose_in_the_car.orientation.pitch,	0, NULL},
		{(char*)"gps_nmea", (char*)"yaw",		CARMEN_PARAM_DOUBLE, &xsens_handler->gps_pose_in_the_car.orientation.yaw,		0, NULL},

	};
	
	num_items = sizeof(param_list) / sizeof(param_list[0]);
	carmen_param_install_params(argc, argv, param_list, num_items);
}
static void 
read_parameters(int argc, char *argv[], carmen_base_ackerman_config_t *config)
{
	int num_items;

	carmen_param_t param_list[]= 
	{
		{"robot", "width", CARMEN_PARAM_DOUBLE, &(config->width), 1, NULL},
		{"robot", "length", CARMEN_PARAM_DOUBLE, &(config->length), 1, NULL},
		{"robot", "distance_between_front_and_rear_axles", CARMEN_PARAM_DOUBLE, &(config->distance_between_front_and_rear_axles), 1,NULL},

		{"robot", "publish_odometry", CARMEN_PARAM_ONOFF, &(config->publish_odometry), 0, NULL},

		{"robot", "phi_multiplier", CARMEN_PARAM_DOUBLE, &phi_multiplier, 0, NULL},
		{"robot", "phi_bias", CARMEN_PARAM_DOUBLE, &phi_bias, 0, NULL},
		{"robot", "v_multiplier", CARMEN_PARAM_DOUBLE, &v_multiplier, 0, NULL},

		{"visual_odometry", "phi_multiplier", CARMEN_PARAM_DOUBLE, &visual_odometry_phi_multiplier, 0, NULL},
		{"visual_odometry", "phi_bias", CARMEN_PARAM_DOUBLE, &visual_odometry_phi_bias, 0, NULL},
		{"visual_odometry", "v_multiplier", CARMEN_PARAM_DOUBLE, &visual_odometry_v_multiplier, 0, NULL},

		{"visual_odometry", "publish", CARMEN_PARAM_DOUBLE, &visual_odometry_publish, 0, NULL}
	};

	num_items = sizeof(param_list) / sizeof(param_list[0]);
	carmen_param_install_params(argc, argv, param_list, num_items);
}
Exemple #4
0
int 
main(int argc, char** argv)
{
  double length;
  char *dev;
  int num_items;
  char **modules;
  int num_modules;

  carmen_param_t param_list[] = {
    {"robot", "length", CARMEN_PARAM_DOUBLE, &length, 1, handler},
    {"scout", "dev", CARMEN_PARAM_STRING, &dev, 1, handler},
  };

  carmen_ipc_initialize(argc, argv);
  carmen_param_check_version(argv[0]);

  signal(SIGINT, shutdown_module);
  
  num_items = sizeof(param_list)/sizeof(param_list[0]);

  carmen_param_install_params(argc, argv, param_list, num_items);
 
  carmen_param_get_robot();
  carmen_param_get_modules(&modules, &num_modules);
 
  carmen_warn("robot_length is %.1f\n", length);
  carmen_warn("scout_dev is %s\n", dev);

  carmen_param_check_unhandled_commandline_args(argc, argv);

  carmen_ipc_dispatch();

  return 0;
}
int 
motion_planner_read_parameters(int argc, char **argv)
{
	int num_items;

	carmen_param_t param_list[] = 
	{
			{"robot", "max_velocity", CARMEN_PARAM_DOUBLE,	&carmen_robot_ackerman_config.max_v, 1, NULL},
			{"robot", "max_steering_angle", CARMEN_PARAM_DOUBLE, &carmen_robot_ackerman_config.max_phi, 1, NULL},
			{"robot", "min_approach_dist", CARMEN_PARAM_DOUBLE,	&carmen_robot_ackerman_config.approach_dist, 1, NULL},
			{"robot", "min_side_dist", CARMEN_PARAM_DOUBLE,	&carmen_robot_ackerman_config.side_dist, 1, NULL},
			{"robot", "length", CARMEN_PARAM_DOUBLE, &carmen_robot_ackerman_config.length, 0, NULL},
			{"robot", "width", CARMEN_PARAM_DOUBLE, &carmen_robot_ackerman_config.width, 0, NULL},
			{"robot", "reaction_time", CARMEN_PARAM_DOUBLE, &carmen_robot_ackerman_config.reaction_time, 0, NULL},
			{"robot", "distance_between_rear_wheels", CARMEN_PARAM_DOUBLE, &carmen_robot_ackerman_config.distance_between_rear_wheels, 1,NULL},
			{"robot", "distance_between_front_and_rear_axles", CARMEN_PARAM_DOUBLE, &carmen_robot_ackerman_config.distance_between_front_and_rear_axles, 1, NULL},
			{"robot", "distance_between_rear_car_and_rear_wheels", CARMEN_PARAM_DOUBLE, &carmen_robot_ackerman_config.distance_between_rear_car_and_rear_wheels, 1, NULL},
			{"robot", "allow_rear_motion", CARMEN_PARAM_ONOFF, &carmen_robot_ackerman_config.allow_rear_motion, 1, NULL},
			{"robot", "interpolate_odometry", CARMEN_PARAM_ONOFF, &carmen_robot_ackerman_config.interpolate_odometry, 1, NULL},
			{"robot", "maximum_acceleration_forward", CARMEN_PARAM_DOUBLE, &(carmen_robot_ackerman_config.maximum_acceleration_forward), 0, NULL},
			{"robot", "maximum_deceleration_forward", CARMEN_PARAM_DOUBLE, &(carmen_robot_ackerman_config.maximum_deceleration_forward), 0, NULL},
			{"robot", "maximum_acceleration_reverse", CARMEN_PARAM_DOUBLE, &(carmen_robot_ackerman_config.maximum_acceleration_reverse), 0, NULL},
			{"robot", "maximum_deceleration_reverse", CARMEN_PARAM_DOUBLE, &(carmen_robot_ackerman_config.maximum_deceleration_reverse), 0, NULL},

			{"robot", "understeer_coeficient", CARMEN_PARAM_DOUBLE, &carmen_robot_ackerman_config.understeer_coeficient, 1, NULL},
			{"robot", "maximum_steering_command_curvature", CARMEN_PARAM_DOUBLE, &carmen_robot_ackerman_config.maximum_steering_command_curvature, 1, NULL},
			{"robot", "maximum_steering_command_rate", CARMEN_PARAM_DOUBLE, &carmen_robot_ackerman_config.maximum_steering_command_rate, 1, NULL},
			{"motion_planner", "phi_gain", CARMEN_PARAM_DOUBLE, &phi_gain, 1, NULL},
	};

	num_items = sizeof(param_list)/sizeof(param_list[0]);
	carmen_param_install_params(argc, argv, param_list, num_items);

	return 0;
}
Exemple #6
0
int robox_read_parameters(int argc, char **argv) {
  int num_params;
  carmen_param_t robox_params[] = {
    {"robox", "security_estop_dev", CARMEN_PARAM_STRING, 
      &robox_security_estop_dev, 0, NULL},
    {"robox", "security_sstop_dev", CARMEN_PARAM_STRING, 
      &robox_security_sstop_dev, 0, NULL},
    {"robox", "security_watchdog_dev", CARMEN_PARAM_STRING, 
      &robox_security_watchdog_dev, 0, NULL},
    {"robox", "security_flashlight_dev", CARMEN_PARAM_STRING, 
      &robox_security_flashlight_dev, 0, NULL},
    {"robox", "power_engage_dev", CARMEN_PARAM_STRING, 
      &robox_power_engage_dev, 0, NULL},
    {"robox", "power_battery_dev", CARMEN_PARAM_STRING, 
      &robox_power_battery_dev, 0, NULL},
    {"robox", "sensors_check_dev", CARMEN_PARAM_STRING, 
      &robox_sensors_check_dev, 0, NULL},
    {"robox", "sensors_ok_dev", CARMEN_PARAM_STRING, 
      &robox_sensors_ok_dev, 0, NULL},
    {"robox", "encoder_right_dev", CARMEN_PARAM_STRING, 
      &robox_encoder_right_dev, 0, NULL},
    {"robox", "encoder_left_dev", CARMEN_PARAM_STRING, 
      &robox_encoder_left_dev, 0, NULL},
    {"robox", "bumper_dev_dir", CARMEN_PARAM_STRING, 
      &robox_bumper_dev_dir, 0, NULL},
    {"robox", "motor_enable_dev", CARMEN_PARAM_STRING, 
      &robox_motor_enable_dev, 0, NULL},
    {"robox", "motor_right_dev", CARMEN_PARAM_STRING, 
      &robox_motor_right_dev, 0, NULL},
    {"robox", "motor_left_dev", CARMEN_PARAM_STRING, 
      &robox_motor_left_dev, 0, NULL},
    {"robox", "motor_brake_dev", CARMEN_PARAM_STRING, 
      &robox_motor_brake_dev, 0, NULL},

    {"robox", "encoder_pulses", CARMEN_PARAM_INT, 
      &robox_encoder_pulses, 0, NULL},
    {"robox", "gear_trans", CARMEN_PARAM_DOUBLE, 
      &robox_gear_trans, 0, NULL},
    {"robox", "wheel_base", CARMEN_PARAM_DOUBLE, 
      &robox_wheel_base, 0, NULL},
    {"robox", "wheel_right_radius", CARMEN_PARAM_DOUBLE, 
      &robox_wheel_right_radius, 0, NULL},
    {"robox", "wheel_left_radius", CARMEN_PARAM_DOUBLE, 
      &robox_wheel_left_radius, 0, NULL},

    {"robox", "control_freq", CARMEN_PARAM_DOUBLE, 
      &robox_control_freq, 0, NULL},
    {"robox", "control_p_gain", CARMEN_PARAM_DOUBLE, 
      &robox_control_p_gain, 0, NULL},
    {"robox", "control_i_gain", CARMEN_PARAM_DOUBLE, 
      &robox_control_i_gain, 0, NULL},
    {"robox", "control_d_gain", CARMEN_PARAM_DOUBLE, 
      &robox_control_d_gain, 0, NULL},
  };

  num_params = sizeof(robox_params)/sizeof(carmen_param_t);
  carmen_param_install_params(argc, argv, robox_params, num_params);

  return num_params;
}
void
carmen_linemapping_get_params( int argc, char **argv, 
			       carmen_linemapping_parameters_t* param )
{
  carmen_param_t param_list[] = {
    
    {"linemapping", "laser_maxrange", CARMEN_PARAM_DOUBLE, 
     &param->laser_max_length, 0, NULL},
    {"linemapping", "sam_tolerance", CARMEN_PARAM_DOUBLE, 
     &param->sam_tolerance, 0, NULL},
    {"linemapping", "sam_max_gap", CARMEN_PARAM_DOUBLE, 
     &param->sam_max_gap, 0, NULL},
    {"linemapping", "sam_min_length", CARMEN_PARAM_DOUBLE, 
     &param->sam_min_length, 0, NULL},
    {"linemapping", "sam_min_num", CARMEN_PARAM_INT, 
     &param->sam_min_num, 0, NULL},
    {"linemapping", "sam_use_fit_split", CARMEN_PARAM_ONOFF, 
     &param->sam_use_fit_split, 0, NULL},

    {"linemapping", "merge_max_dist", CARMEN_PARAM_DOUBLE, 
     &param->merge_max_dist, 0, NULL},
    {"linemapping", "merge_min_relative_overlap", CARMEN_PARAM_DOUBLE, 
     &param->merge_min_relative_overlap, 0, NULL},
    {"linemapping", "merge_overlap_min_length", CARMEN_PARAM_DOUBLE, 
     &param->merge_overlap_min_length, 0, NULL},
    {"linemapping", "merge_uniformly_distribute_dist", CARMEN_PARAM_DOUBLE, 
     &param->merge_uniformly_distribute_dist, 0, NULL}
    
  };

  carmen_param_install_params(argc, argv, param_list, 
                              sizeof(param_list) / sizeof(param_list[0]));
                              
}
Exemple #8
0
static void
initialize_carmen_parameters(int argc, char** argv)
{
	int num_items;

	carmen_param_t param_list[] = 
	{
		{(char*)"velodyne", (char*)"x",			CARMEN_PARAM_DOUBLE, &velodyne_pose.position.x,		0, NULL},
		{(char*)"velodyne", (char*)"y",			CARMEN_PARAM_DOUBLE, &velodyne_pose.position.y,		0, NULL},
		{(char*)"velodyne", (char*)"z",			CARMEN_PARAM_DOUBLE, &velodyne_pose.position.z,		0, NULL},
		{(char*)"velodyne", (char*)"roll",		CARMEN_PARAM_DOUBLE, &velodyne_pose.orientation.roll,	0, NULL},
		{(char*)"velodyne", (char*)"pitch",		CARMEN_PARAM_DOUBLE, &velodyne_pose.orientation.pitch,	0, NULL},
		{(char*)"velodyne", (char*)"yaw",		CARMEN_PARAM_DOUBLE, &velodyne_pose.orientation.yaw,	0, NULL},
		{(char*)"sensor_board_1", (char*)"x",		CARMEN_PARAM_DOUBLE, &sensor_board_pose.position.x,	0, NULL},
		{(char*)"sensor_board_1", (char*)"y",		CARMEN_PARAM_DOUBLE, &sensor_board_pose.position.y,	0, NULL},
		{(char*)"sensor_board_1", (char*)"z",		CARMEN_PARAM_DOUBLE, &sensor_board_pose.position.z,	0, NULL},
		{(char*)"sensor_board_1", (char*)"roll",	CARMEN_PARAM_DOUBLE, &sensor_board_pose.orientation.roll,0, NULL},
		{(char*)"sensor_board_1", (char*)"pitch",	CARMEN_PARAM_DOUBLE, &sensor_board_pose.orientation.pitch,0, NULL},
		{(char*)"sensor_board_1", (char*)"yaw",		CARMEN_PARAM_DOUBLE, &sensor_board_pose.orientation.yaw,0, NULL},

	};
	
	num_items = sizeof(param_list) / sizeof(param_list[0]);

	carmen_param_install_params(argc, argv, param_list, num_items);
}
static void
read_parameters(int argc, char **argv)
{
	carmen_param_t param_list[] = {
			{(char *)"command_line",	 (char *)"map_path",	CARMEN_PARAM_STRING, &map_path,	 1, NULL},
	};
	carmen_param_install_params(argc, argv, param_list, sizeof(param_list) / sizeof(param_list[0]));
}
Exemple #10
0
CarDrawer* createCarDrawer(int argc, char** argv)
{	
	CarDrawer* carDrawer = malloc(sizeof(CarDrawer));

	carDrawer->carModel = glmReadOBJ("ford_escape_model.obj");
	glmUnitize(carDrawer->carModel);

	int num_items;

	carmen_param_t param_list[] = {
	{"carmodel", "size_x", CARMEN_PARAM_DOUBLE, &(carDrawer->car_size.x), 0, NULL},
	{"carmodel", "size_y", CARMEN_PARAM_DOUBLE, &(carDrawer->car_size.y), 0, NULL},
	{"carmodel", "size_z", CARMEN_PARAM_DOUBLE, &(carDrawer->car_size.z), 0, NULL},
	{"carmodel", "x", CARMEN_PARAM_DOUBLE, &(carDrawer->car_pose.position.x), 0, NULL},
	{"carmodel", "y", CARMEN_PARAM_DOUBLE, &(carDrawer->car_pose.position.y), 0, NULL},
	{"carmodel", "z", CARMEN_PARAM_DOUBLE, &(carDrawer->car_pose.position.z), 0, NULL},
	{"carmodel", "roll", CARMEN_PARAM_DOUBLE, &(carDrawer->car_pose.orientation.roll), 0, NULL},
	{"carmodel", "pitch", CARMEN_PARAM_DOUBLE, &(carDrawer->car_pose.orientation.pitch), 0, NULL},
	{"carmodel", "yaw", CARMEN_PARAM_DOUBLE, &(carDrawer->car_pose.orientation.yaw), 0, NULL},
	{"car", "axis_distance", CARMEN_PARAM_DOUBLE, &(carDrawer->car_axis_distance), 0, NULL},
	{"car", "wheel_diameter", CARMEN_PARAM_DOUBLE, &(carDrawer->car_wheel_diameter), 0, NULL},

	{"sensor_board_1", "x", CARMEN_PARAM_DOUBLE, &(carDrawer->sensor_board_1_pose.position.x), 0, NULL},
	{"sensor_board_1", "y", CARMEN_PARAM_DOUBLE, &(carDrawer->sensor_board_1_pose.position.y), 0, NULL},
	{"sensor_board_1", "z", CARMEN_PARAM_DOUBLE, &(carDrawer->sensor_board_1_pose.position.z), 0, NULL},
	{"sensor_board_1", "roll", CARMEN_PARAM_DOUBLE, &(carDrawer->sensor_board_1_pose.orientation.roll), 0, NULL},
	{"sensor_board_1", "pitch", CARMEN_PARAM_DOUBLE, &(carDrawer->sensor_board_1_pose.orientation.pitch), 0, NULL},
	{"sensor_board_1", "yaw", CARMEN_PARAM_DOUBLE, &(carDrawer->sensor_board_1_pose.orientation.yaw), 0, NULL},

	{"xsens", "size_x", CARMEN_PARAM_DOUBLE, &(carDrawer->xsens_size.x), 0, NULL},
	{"xsens", "size_y", CARMEN_PARAM_DOUBLE, &(carDrawer->xsens_size.y), 0, NULL},
	{"xsens", "size_z", CARMEN_PARAM_DOUBLE, &(carDrawer->xsens_size.z), 0, NULL},
	{"xsens", "x", CARMEN_PARAM_DOUBLE, &(carDrawer->xsens_pose.position.x), 0, NULL},
	{"xsens", "y", CARMEN_PARAM_DOUBLE, &(carDrawer->xsens_pose.position.y), 0, NULL},
	{"xsens", "z", CARMEN_PARAM_DOUBLE, &(carDrawer->xsens_pose.position.z), 0, NULL},
	{"xsens", "roll", CARMEN_PARAM_DOUBLE, &(carDrawer->xsens_pose.orientation.roll), 0, NULL},
	{"xsens", "pitch", CARMEN_PARAM_DOUBLE, &(carDrawer->xsens_pose.orientation.pitch), 0, NULL},
	{"xsens", "yaw", CARMEN_PARAM_DOUBLE, &(carDrawer->xsens_pose.orientation.yaw), 0, NULL},	

	{"laser", "size_x", CARMEN_PARAM_DOUBLE, &(carDrawer->laser_size.x), 0, NULL},
	{"laser", "size_y", CARMEN_PARAM_DOUBLE, &(carDrawer->laser_size.y), 0, NULL},
	{"laser", "size_z", CARMEN_PARAM_DOUBLE, &(carDrawer->laser_size.z), 0, NULL},
	{"velodyne", "x", CARMEN_PARAM_DOUBLE, &(carDrawer->laser_pose.position.x), 0, NULL},
	{"velodyne", "y", CARMEN_PARAM_DOUBLE, &(carDrawer->laser_pose.position.y), 0, NULL},
	{"velodyne", "z", CARMEN_PARAM_DOUBLE, &(carDrawer->laser_pose.position.z), 0, NULL},
	{"velodyne", "roll", CARMEN_PARAM_DOUBLE, &(carDrawer->laser_pose.orientation.roll), 0, NULL},
	{"velodyne", "pitch", CARMEN_PARAM_DOUBLE, &(carDrawer->laser_pose.orientation.pitch), 0, NULL},
	{"velodyne", "yaw", CARMEN_PARAM_DOUBLE, &(carDrawer->laser_pose.orientation.yaw), 0, NULL}
	};
	
	num_items = sizeof(param_list)/sizeof(param_list[0]);
	carmen_param_install_params(argc, argv, param_list, num_items);

	glmScale(carDrawer->carModel, carDrawer->car_size.x/2.0);

	return carDrawer;
}
Exemple #11
0
void
read_parameters(int argc, char **argv)
{
	carmen_param_t param_list[] = {
			{(char *)"robot",	(char *)"length",								  		CARMEN_PARAM_DOUBLE, &GlobalState::robot_config.length,								 			1, NULL},
			{(char *)"robot",	(char *)"width",								  		CARMEN_PARAM_DOUBLE, &GlobalState::robot_config.width,								 			1, NULL},
			{(char *)"robot", 	(char *)"distance_between_rear_wheels",		  			CARMEN_PARAM_DOUBLE, &GlobalState::robot_config.distance_between_rear_wheels,			 		1, NULL},
			{(char *)"robot", 	(char *)"distance_between_front_and_rear_axles", 		CARMEN_PARAM_DOUBLE, &GlobalState::robot_config.distance_between_front_and_rear_axles, 			1, NULL},
			{(char *)"robot", 	(char *)"distance_between_front_car_and_front_wheels",	CARMEN_PARAM_DOUBLE, &GlobalState::robot_config.distance_between_front_car_and_front_wheels,	1, NULL},
			{(char *)"robot", 	(char *)"distance_between_rear_car_and_rear_wheels",	CARMEN_PARAM_DOUBLE, &GlobalState::robot_config.distance_between_rear_car_and_rear_wheels,		1, NULL},
			{(char *)"robot", 	(char *)"max_velocity",						  			CARMEN_PARAM_DOUBLE, &GlobalState::robot_config.max_vel,								 		1, NULL},
			{(char *)"robot", 	(char *)"max_steering_angle",					  		CARMEN_PARAM_DOUBLE, &GlobalState::robot_config.max_phi,								 		1, NULL},
			{(char *)"robot", 	(char *)"maximum_acceleration_forward",					CARMEN_PARAM_DOUBLE, &GlobalState::robot_config.maximum_acceleration_forward,					1, NULL},
			{(char *)"robot", 	(char *)"maximum_acceleration_reverse",					CARMEN_PARAM_DOUBLE, &GlobalState::robot_config.maximum_acceleration_reverse,					1, NULL},
			{(char *)"robot", 	(char *)"maximum_deceleration_forward",					CARMEN_PARAM_DOUBLE, &GlobalState::robot_config.maximum_deceleration_forward,					1, NULL},
			{(char *)"robot", 	(char *)"maximum_deceleration_reverse",					CARMEN_PARAM_DOUBLE, &GlobalState::robot_config.maximum_deceleration_reverse,					1, NULL},
			{(char *)"robot", 	(char *)"desired_decelaration_forward",					CARMEN_PARAM_DOUBLE, &GlobalState::robot_config.desired_decelaration_forward,					1, NULL},
			{(char *)"robot", 	(char *)"desired_decelaration_reverse",					CARMEN_PARAM_DOUBLE, &GlobalState::robot_config.desired_decelaration_reverse,					1, NULL},
			{(char *)"robot", 	(char *)"desired_acceleration",							CARMEN_PARAM_DOUBLE, &GlobalState::robot_config.desired_acceleration,							1, NULL},
			{(char *)"robot", 	(char *)"desired_steering_command_rate",				CARMEN_PARAM_DOUBLE, &GlobalState::robot_config.desired_steering_command_rate,					1, NULL},
			{(char *)"robot", 	(char *)"understeer_coeficient",						CARMEN_PARAM_DOUBLE, &GlobalState::robot_config.understeer_coeficient,							1, NULL},
	};

	carmen_param_install_params(argc, argv, param_list, sizeof(param_list) / sizeof(param_list[0]));

	GlobalState::param_max_vel = GlobalState::robot_config.max_vel;

	//initialize default parameters values
	GlobalState::cheat = 0;

	GlobalState::timeout = 0.8;
	GlobalState::distance_interval = 1.5;
	GlobalState::plan_time = 0.08;

	carmen_param_t optional_param_list[] = {
			{(char *)"rrt",	(char *)"cheat",				CARMEN_PARAM_ONOFF,		&GlobalState::cheat,				1, NULL},
			{(char *)"rrt",	(char *)"show_debug_info",		CARMEN_PARAM_ONOFF,		&GlobalState::show_debug_info,		1, NULL},
	};

	carmen_param_allow_unfound_variables(1);
	carmen_param_install_params(argc, argv, optional_param_list, sizeof(optional_param_list) / sizeof(optional_param_list[0]));

	read_parameters_specific(argc, argv);
}
static void 
initialize_carmen_parameters(int argc, char** argv, carmen_fused_odometry_parameters *fused_odometry_parameters)
{
	int num_items;

	carmen_param_t param_list[] = 
	{
		{(char *) "fused_odometry", 	(char *) "num_particles", CARMEN_PARAM_INT, &num_particles, 0, NULL},
		{(char *) "fused_odometry", 	(char *) "frequency", CARMEN_PARAM_DOUBLE, &fused_odometry_frequency, 0, NULL},
		{(char *) "fused_odometry", 	(char *) "use_viso_odometry", CARMEN_PARAM_INT, &use_viso_odometry, 0, NULL},
		{(char *) "fused_odometry", 	(char *) "use_car_odometry", CARMEN_PARAM_INT, &use_car_odometry, 0, NULL},	

		{(char *) "fused_odometry", 	(char *) "velocity_noise_velocity", CARMEN_PARAM_DOUBLE, &fused_odometry_parameters->velocity_noise_velocity, 0, NULL},
		{(char *) "fused_odometry", 	(char *) "velocity_noise_phi", CARMEN_PARAM_DOUBLE, &fused_odometry_parameters->velocity_noise_phi, 0, NULL},
		{(char *) "fused_odometry", 	(char *) "phi_noise_phi", CARMEN_PARAM_DOUBLE, &fused_odometry_parameters->phi_noise_phi, 0, NULL},
		{(char *) "fused_odometry", 	(char *) "phi_noise_velocity", CARMEN_PARAM_DOUBLE, &fused_odometry_parameters->phi_noise_velocity, 0, NULL},
		{(char *) "fused_odometry", 	(char *) "pitch_v_noise_pitch_v", CARMEN_PARAM_DOUBLE, &fused_odometry_parameters->pitch_v_noise_pitch_v, 0, NULL},
		{(char *) "fused_odometry", 	(char *) "pitch_v_noise_velocity", CARMEN_PARAM_DOUBLE, &fused_odometry_parameters->pitch_v_noise_velocity, 0, NULL},

		{(char *) "fused_odometry", 	(char *) "minimum_speed_for_correction", CARMEN_PARAM_DOUBLE, &fused_odometry_parameters->minimum_speed_for_correction, 0, NULL},
		{(char *) "fused_odometry", 	(char *) "xsens_yaw_bias_noise", CARMEN_PARAM_DOUBLE, &fused_odometry_parameters->xsens_yaw_bias_noise, 0, NULL},
		{(char *) "fused_odometry", 	(char *) "xsens_maximum_yaw_bias", CARMEN_PARAM_DOUBLE, &fused_odometry_parameters->xsens_maximum_yaw_bias, 0, NULL},
		{(char *) "fused_odometry", 	(char *) "maximum_phi", CARMEN_PARAM_DOUBLE, &fused_odometry_parameters->maximum_phi, 0, NULL},
		
		{(char *) "fused_odometry", 	(char *) "xsens_gps_x_std_error", CARMEN_PARAM_DOUBLE, &fused_odometry_parameters->xsens_gps_x_std_error, 0, NULL},	
		{(char *) "fused_odometry", 	(char *) "xsens_gps_y_std_error", CARMEN_PARAM_DOUBLE, &fused_odometry_parameters->xsens_gps_y_std_error, 0, NULL},	
		{(char *) "fused_odometry", 	(char *) "xsens_gps_z_std_error", CARMEN_PARAM_DOUBLE, &fused_odometry_parameters->xsens_gps_z_std_error, 0, NULL},	

		{(char *) "fused_odometry", 	(char *) "xsens_roll_std_error", CARMEN_PARAM_DOUBLE, &fused_odometry_parameters->xsens_roll_std_error, 0, NULL},	
		{(char *) "fused_odometry", 	(char *) "xsens_pitch_std_error", CARMEN_PARAM_DOUBLE, &fused_odometry_parameters->xsens_pitch_std_error, 0, NULL},	
		{(char *) "fused_odometry", 	(char *) "xsens_yaw_std_error", CARMEN_PARAM_DOUBLE, &fused_odometry_parameters->xsens_yaw_std_error, 0, NULL},	

		{(char *) "fused_odometry", 	(char *) "kalman_filter", CARMEN_PARAM_ONOFF, &kalman_filter, 0, NULL},

		{(char *) "robot", 	    	(char *) "distance_between_front_and_rear_axles", CARMEN_PARAM_DOUBLE, &fused_odometry_parameters->axis_distance, 0, NULL},
	};
	
	num_items = sizeof(param_list) / sizeof(param_list[0]);
	carmen_param_install_params(argc, argv, param_list, num_items);

	fused_odometry_parameters->velocity_noise_phi = carmen_degrees_to_radians(fused_odometry_parameters->velocity_noise_phi);
	fused_odometry_parameters->phi_noise_phi = carmen_degrees_to_radians(fused_odometry_parameters->phi_noise_phi);
	fused_odometry_parameters->phi_noise_velocity = carmen_degrees_to_radians(fused_odometry_parameters->phi_noise_velocity);

	fused_odometry_parameters->pitch_v_noise_pitch_v = carmen_degrees_to_radians(fused_odometry_parameters->pitch_v_noise_pitch_v);
	fused_odometry_parameters->pitch_v_noise_velocity = carmen_degrees_to_radians(fused_odometry_parameters->pitch_v_noise_velocity);

	fused_odometry_parameters->xsens_yaw_bias_noise = carmen_degrees_to_radians(fused_odometry_parameters->xsens_yaw_bias_noise);
	fused_odometry_parameters->xsens_maximum_yaw_bias = carmen_degrees_to_radians(fused_odometry_parameters->xsens_maximum_yaw_bias);
	fused_odometry_parameters->maximum_phi = carmen_degrees_to_radians(fused_odometry_parameters->maximum_phi);

	fused_odometry_parameters->xsens_roll_std_error = carmen_degrees_to_radians(fused_odometry_parameters->xsens_roll_std_error);
	fused_odometry_parameters->xsens_pitch_std_error = carmen_degrees_to_radians(fused_odometry_parameters->xsens_pitch_std_error);
	fused_odometry_parameters->xsens_yaw_std_error = carmen_degrees_to_radians(fused_odometry_parameters->xsens_yaw_std_error);
}
static void
carmen_rddf_build_get_parameters (int argc, char** argv)
{
	carmen_param_t param_list[] = {
			{(char *)"rddf", (char *)"min_distance_between_waypoints", CARMEN_PARAM_DOUBLE, &carmen_rddf_min_distance_between_waypoints, 1, NULL},
			{(char *)"robot", (char *)"max_velocity", CARMEN_PARAM_DOUBLE, &carmen_rddf_max_velocity, 1, NULL},
	};

	int num_items = sizeof(param_list) / sizeof(param_list[0]);
	carmen_param_install_params(argc, argv, param_list, num_items);
}
Exemple #14
0
int
carmen_laslam_read_parameters(int argc, char **argv)
{
	int num_items;
	char bumblebee_string[256];
	char camera_string[256];

	if (argc < 2)
		printf("usage: ./laslam <camera>\n");

	sprintf(bumblebee_string, "%s%d", "bumblebee_basic", atoi(argv[1]));
	sprintf(camera_string, "%s%d", "camera", atoi(argv[1]));

	carmen_param_t param_list[] =
	{
			{(char *) "carmodel", (char *) "size_x", CARMEN_PARAM_DOUBLE, &(robot_size_g.x), 0, NULL},
			{(char *) "carmodel", (char *) "size_y", CARMEN_PARAM_DOUBLE, &(robot_size_g.y), 0, NULL},
			{(char *) "carmodel", (char *) "size_z", CARMEN_PARAM_DOUBLE, &(robot_size_g.z), 0, NULL},
			{(char *) bumblebee_string, (char *) "width", CARMEN_PARAM_INT, &(image_width), 0, NULL},
			{(char *) bumblebee_string, (char *) "height", CARMEN_PARAM_INT, &(image_height), 0, NULL},

			{(char *) "car", (char *) "x", CARMEN_PARAM_DOUBLE, &(car_pose_g.position.x), 0, NULL},
			{(char *) "car", (char *) "y", CARMEN_PARAM_DOUBLE, &(car_pose_g.position.y), 0, NULL},
			{(char *) "car", (char *) "z", CARMEN_PARAM_DOUBLE, &(car_pose_g.position.z), 0, NULL},
			{(char *) "car", (char *) "yaw", CARMEN_PARAM_DOUBLE, &(car_pose_g.orientation.yaw), 0, NULL},
			{(char *) "car", (char *) "pitch", CARMEN_PARAM_DOUBLE, &(car_pose_g.orientation.pitch), 0, NULL},
			{(char *) "car", (char *) "roll", CARMEN_PARAM_DOUBLE, &(car_pose_g.orientation.roll), 0, NULL},

			{(char *) "sensor_board_1", (char *) "x", CARMEN_PARAM_DOUBLE, &(board_pose_g.position.x), 0, NULL},
			{(char *) "sensor_board_1", (char *) "y", CARMEN_PARAM_DOUBLE, &(board_pose_g.position.y), 0, NULL},
			{(char *) "sensor_board_1", (char *) "z", CARMEN_PARAM_DOUBLE, &(board_pose_g.position.z), 0, NULL},
			{(char *) "sensor_board_1", (char *) "yaw", CARMEN_PARAM_DOUBLE, &(board_pose_g.orientation.yaw), 0, NULL},
			{(char *) "sensor_board_1", (char *) "pitch", CARMEN_PARAM_DOUBLE, &(board_pose_g.orientation.pitch), 0, NULL},
			{(char *) "sensor_board_1", (char *) "roll", CARMEN_PARAM_DOUBLE, &(board_pose_g.orientation.roll), 0, NULL},

			{(char *) camera_string, (char *) "x", CARMEN_PARAM_DOUBLE, &(camera_pose_g.position.x), 0, NULL},
			{(char *) camera_string, (char *) "y", CARMEN_PARAM_DOUBLE, &(camera_pose_g.position.y), 0, NULL},
			{(char *) camera_string, (char *) "z", CARMEN_PARAM_DOUBLE, &(camera_pose_g.position.z), 0, NULL},
			{(char *) camera_string, (char *) "yaw", CARMEN_PARAM_DOUBLE, &(camera_pose_g.orientation.yaw), 0, NULL},
			{(char *) camera_string, (char *) "pitch", CARMEN_PARAM_DOUBLE, &(camera_pose_g.orientation.pitch), 0, NULL},
			{(char *) camera_string, (char *) "roll", CARMEN_PARAM_DOUBLE, &(camera_pose_g.orientation.roll), 0, NULL},
	};


	num_items = sizeof(param_list)/sizeof(param_list[0]);
	carmen_param_install_params(argc, argv, param_list, num_items);

	camera_parameters = get_stereo_instance(atoi(argv[1]), image_width, image_height);

	return 0;
}
static void
read_parameters(int argc, char **argv)
{
	carmen_param_allow_unfound_variables(1);

	carmen_param_t param_list[] = 
	{
			{(char *)"commandline",	 (char *)"map_path",		CARMEN_PARAM_STRING, &map_path,	 	1, NULL},
			{(char *)"commandline",	 (char *)"map_resolution",	CARMEN_PARAM_DOUBLE, &map_resolution,	1, NULL},
			{(char *)"commandline",	 (char *)"map_type",		CARMEN_PARAM_STRING, &map_type,		1, NULL},

	};
	carmen_param_install_params(argc, argv, param_list, sizeof(param_list) / sizeof(param_list[0]));
}
Exemple #16
0
void read_parameters(int argc, char **argv)
{
  carmen_param_t camera_params[] = {
    {"camera", "dev", CARMEN_PARAM_STRING, &camera_dev, 0, NULL},
    {"camera", "image_width", CARMEN_PARAM_INT, &image_width, 0, NULL},
    {"camera", "image_height", CARMEN_PARAM_INT, &image_height, 0, NULL},
    {"camera", "brightness", CARMEN_PARAM_INT, &brightness, 0, NULL},
    {"camera", "hue", CARMEN_PARAM_INT, &hue, 0, NULL},
    {"camera", "saturation", CARMEN_PARAM_INT, &saturation, 0, NULL},
    {"camera", "contrast", CARMEN_PARAM_INT, &contrast, 0, NULL},
    {"camera", "gamma", CARMEN_PARAM_INT, &camera_gamma, 0, NULL},
    {"camera", "denoisestrength", CARMEN_PARAM_INT, &denoisestrength, 0, NULL},
    {"camera", "awbmode", CARMEN_PARAM_STRING, &awbmode, 0, NULL},
    {"camera", "antiflicker", CARMEN_PARAM_ONOFF, &antiflicker, 0, NULL},
    {"camera", "backlightcompensation", CARMEN_PARAM_ONOFF, &backlightcompensation, 0, NULL},
    {"camera", "useautosharpen", CARMEN_PARAM_ONOFF, &useautosharpen, 0, NULL},
    {"camera", "useautoshutter", CARMEN_PARAM_ONOFF, &useautoshutter, 0, NULL},
    {"camera", "useagc", CARMEN_PARAM_ONOFF, &useagc, 0, NULL},
    {"camera", "fps", CARMEN_PARAM_INT, &fps, 0, NULL}};

  carmen_param_install_params(argc, argv, camera_params, 
			      sizeof(camera_params) / 
			      sizeof(camera_params[0]));

  carmen_param_set_module("camera");
  if (!useautosharpen) {
    if (carmen_param_get_int("sharpenstrength", &sharpenstrength,NULL) < 0)
      carmen_die("camera_sharpenstrength must be specified or "
		 "carmen_useautosharpen\nmust be turned on\n");
  }
  if (!useautoshutter) {
    if (carmen_param_get_int("shutterlength", &shutterlength,NULL) < 0)
      carmen_die("camera_shutterlength must be specified or "
		 "carmen_useautoshutter\nmust be turned on\n");
  }
  if (!useagc) {
    if (carmen_param_get_int("gain", &gain,NULL) < 0)
      carmen_die("camera_gain must be specified or carmen_useagc\n"
		 "must be turned on\n");
  }
  if(carmen_strcasecmp(awbmode, "Custom") == 0) {
    if (carmen_param_get_int("awbred", &awbred,NULL) < 0)
      carmen_die("camera_awbred must be specified or carmen_awbmode\n"
		 "cannot be set to custom.\n");
    if (carmen_param_get_int("awbblue", &awbblue,NULL) < 0)
      carmen_die("camera_awbblue must be specified or carmen_awbmode\n"
		 "cannot be set to custom.\n");
  }
}
static void
read_parameters(int argc, char **argv)
{
	int num_items;
	carmen_navigator_ackerman_astar_t astar_config;


	carmen_param_t param_list[] = 
	{
			{(char *)"robot",				(char *)"max_velocity", CARMEN_PARAM_DOUBLE, &robot_config.max_v, 1, NULL},//todo add max_v and max_phi in carmen.ini
			{(char *)"robot",				(char *)"max_steering_angle", CARMEN_PARAM_DOUBLE, &robot_config.max_phi, 1, NULL},
			{(char *)"robot",				(char *)"min_approach_dist", CARMEN_PARAM_DOUBLE, &robot_config.approach_dist, 1, NULL},
			{(char *)"robot",				(char *)"min_side_dist", CARMEN_PARAM_DOUBLE, &robot_config.side_dist, 1, NULL},
			{(char *)"robot",				(char *)"length", CARMEN_PARAM_DOUBLE, &robot_config.length, 0, NULL},
			{(char *)"robot",				(char *)"width", CARMEN_PARAM_DOUBLE, &robot_config.width, 0, NULL},
			{(char *)"robot",				(char *)"maximum_acceleration_forward", CARMEN_PARAM_DOUBLE, &robot_config.maximum_acceleration_forward, 1, NULL},
			{(char *)"robot",				(char *)"reaction_time", CARMEN_PARAM_DOUBLE,	&robot_config.reaction_time, 0, NULL},
			{(char *)"robot",				(char *)"distance_between_front_and_rear_axles", CARMEN_PARAM_DOUBLE, &robot_config.distance_between_front_and_rear_axles, 1, NULL},
			{(char *)"robot",				(char *)"maximum_steering_command_rate", CARMEN_PARAM_DOUBLE, &robot_config.maximum_steering_command_rate, 1, NULL},
			{(char *)"robot",				(char *)"distance_between_rear_car_and_rear_wheels", CARMEN_PARAM_DOUBLE, &robot_config.distance_between_rear_car_and_rear_wheels, 1, NULL},
			{(char *)"navigator",			(char *)"goal_size", CARMEN_PARAM_DOUBLE, &nav_config.goal_size, 1, NULL},
			{(char *)"navigator",			(char *)"waypoint_tolerance", CARMEN_PARAM_DOUBLE, &nav_config.waypoint_tolerance, 1, NULL},
			{(char *)"navigator",			(char *)"goal_theta_tolerance", CARMEN_PARAM_DOUBLE, &nav_config.goal_theta_tolerance, 1, NULL},
			{(char *)"navigator",			(char *)"map_update_radius", CARMEN_PARAM_DOUBLE,	&nav_config.map_update_radius, 1, NULL},
			{(char *)"navigator",			(char *)"map_update_num_laser_beams", CARMEN_PARAM_INT, &nav_config.num_lasers_to_use, 1, NULL},
			{(char *)"navigator",			(char *)"map_update_obstacles", CARMEN_PARAM_ONOFF, &nav_config.map_update_obstacles, 1, NULL},
			{(char *)"navigator",			(char *)"map_update_freespace", CARMEN_PARAM_ONOFF, &nav_config.map_update_freespace, 1, NULL},
			{(char *)"navigator",			(char *)"replan_frequency", CARMEN_PARAM_DOUBLE, &nav_config.replan_frequency, 1, NULL},
			{(char *)"navigator",			(char *)"smooth_path", CARMEN_PARAM_ONOFF, &nav_config.smooth_path, 1, NULL},
			{(char *)"navigator",			(char *)"dont_integrate_odometry", CARMEN_PARAM_ONOFF, &nav_config.dont_integrate_odometry, 1, NULL},
			{(char *)"navigator",			(char *)"plan_to_nearest_free_point", CARMEN_PARAM_ONOFF,	&nav_config.plan_to_nearest_free_point, 1, NULL},
			{(char *)"navigator",			(char *)"map", CARMEN_PARAM_STRING, &nav_config.navigator_map, 0, NULL},
			{(char *)"navigator",			(char *)"superimposed_map", CARMEN_PARAM_STRING, &nav_config.superimposed_map, 0, NULL},
			{(char *)"navigator_astar",		(char *)"path_interval", CARMEN_PARAM_DOUBLE, &astar_config.path_interval, 1, NULL},
			{(char *)"navigator_astar",		(char *)"state_map_resolution", CARMEN_PARAM_INT, &astar_config.state_map_resolution, 1, NULL},
			{(char *)"navigator_astar",		(char *)"state_map_theta_resolution", CARMEN_PARAM_INT, &astar_config.state_map_theta_resolution, 1, NULL},
			{(char *)"navigator_astar",		(char *)"precomputed_cost_size", CARMEN_PARAM_INT, &astar_config.precomputed_cost_size, 1, NULL},
			{(char *)"navigator_astar",		(char *)"precomputed_cost_file_name", CARMEN_PARAM_STRING, &astar_config.precomputed_cost_file_name, 1, NULL},
			{(char *)"navigator_astar",		(char *)"use_rs", CARMEN_PARAM_ONOFF, &astar_config.use_rs, 1, NULL},
			{(char *)"navigator_astar",		(char *)"smooth_path", CARMEN_PARAM_ONOFF, &astar_config.smooth_path, 1, NULL},
			{(char *)"navigator_astar",		(char *)"onroad_max_plan_time", CARMEN_PARAM_DOUBLE, &astar_config.onroad_max_plan_time, 1, NULL},
			{(char *)"navigator_astar",		(char *)"robot_fat_space", CARMEN_PARAM_DOUBLE, &astar_config.robot_fat_space, 1, NULL},
	};

	num_items = sizeof(param_list)/sizeof(param_list[0]);
	carmen_param_install_params(argc, argv, param_list, num_items);

	messageControl.initAstarParans(astar_config);
}
Exemple #18
0
static int read_parameters(int argc, char **argv)
{
	int num_items;

	carmen_param_t param_list[] = {
		{(char*)"xsens_mti", (char*)"mode", CARMEN_PARAM_INT, &mode, 0, NULL},
		{(char*)"xsens_mti", (char*)"settings", CARMEN_PARAM_INT, &settings, 0, NULL},
		{(char*)"xsens_mti", (char*)"dev", CARMEN_PARAM_STRING, &dev, 0, NULL}
		};

	num_items = sizeof(param_list)/sizeof(param_list[0]);
	carmen_param_install_params(argc, argv, param_list, num_items);

	return 0;
}
void
localize_ackerman_velodyne_laser_read_parameters(int argc, char **argv)
{
	static char frontlaser_fov_string[256];
	static char frontlaser_res_string[256];

	carmen_param_t param_list[] =
	{
			{(char *)"robot", (char*)"frontlaser_id", CARMEN_PARAM_INT, &(front_laser_config.id), 0, NULL}
	};

	carmen_param_install_params(argc, argv, param_list, sizeof(param_list) / sizeof(param_list[0]));

	sprintf(frontlaser_fov_string, (char*)"laser%d_fov", front_laser_config.id);
	sprintf(frontlaser_res_string, (char*)"laser%d_resolution", front_laser_config.id);

	carmen_param_t param_list_front_laser[] =
	{
			{(char *)"simulator", (char*)"frontlaser_maxrange", CARMEN_PARAM_DOUBLE, &(front_laser_config.max_range), 1, NULL},
			{(char *)"robot", (char*)"frontlaser_offset", CARMEN_PARAM_DOUBLE, &(front_laser_config.offset), 1, NULL},
			{(char *)"robot", (char*)"frontlaser_side_offset", CARMEN_PARAM_DOUBLE, &(front_laser_config.side_offset), 1, NULL},
			{(char *)"robot", (char*)"frontlaser_angular_offset", CARMEN_PARAM_DOUBLE, &(front_laser_config.angular_offset), 1, NULL},
			{(char *)"laser", frontlaser_fov_string, CARMEN_PARAM_DOUBLE, &(front_laser_config.fov), 0, NULL},
			{(char *)"laser", frontlaser_res_string, CARMEN_PARAM_DOUBLE, &(front_laser_config.angular_resolution), 0, NULL},
	};

	carmen_param_install_params(argc, argv, param_list_front_laser, sizeof(param_list_front_laser) / sizeof(param_list_front_laser[0]));

	front_laser_config.angular_resolution =	carmen_degrees_to_radians(front_laser_config.angular_resolution);

	front_laser_config.fov = carmen_degrees_to_radians(front_laser_config.fov);

	fill_laser_config_data(&front_laser_config);

	localize_ackerman_velodyne_laser_initialize();
}
void Carmen_Thread::read_parameters(int argc, char *argv[]) {
    Robot_Config* robot_config = Carmen_State::get_instance()->robot_config;
    int num_items;
    carmen_param_t param_list[] = {
        {(char*)"robot", (char*)"length", CARMEN_PARAM_DOUBLE, &robot_config->length, 1, NULL},
        {(char*)"robot", (char*)"width", CARMEN_PARAM_DOUBLE, &robot_config->width, 1, NULL},
        {(char*)"robot", (char*)"distance_between_rear_wheels", CARMEN_PARAM_DOUBLE, &robot_config->distance_between_rear_wheels, 1,NULL},
        {(char*)"robot", (char*)"distance_between_front_and_rear_axles", CARMEN_PARAM_DOUBLE, &robot_config->distance_between_front_and_rear_axles, 1, NULL}
    };

    num_items = sizeof(param_list)/sizeof(param_list[0]);

    carmen_param_install_params(argc, argv, param_list, num_items);

}
Exemple #21
0
int carmen_velodyne_read_parameters(int argc, char **argv) {
  char module[] = "velodyne";
  int num_params;

  char dev_name_var [256], spin_rate_var[256];
  char calib_filename_var[256], dump_enabled_var[256], dump_dirname_var[256];
  char points_publish_var[256];

  if (argc == 2)
    id = atoi(argv[1]);

  sprintf(dev_name_var, "velodyne%d_dev", id);
  sprintf(spin_rate_var, "velodyne%d_spin_rate", id);
  sprintf(calib_filename_var, "velodyne%d_calib_file", id);
  sprintf(dump_enabled_var, "velodyne%d_dump_enable", id);
  sprintf(dump_dirname_var, "velodyne%d_dump_dir", id);
  sprintf(points_publish_var, "velodyne%d_points_publish", id);

  carmen_param_t params[] = {
    {module, dev_name_var, CARMEN_PARAM_STRING, &dev_name, 1, 0},
    {module, spin_rate_var, CARMEN_PARAM_INT, &spin_rate, 1,
      carmen_velodyne_spin_rate_handler},
    {module, calib_filename_var, CARMEN_PARAM_FILE, &calib_filename, 1, 0},
    {module, dump_enabled_var, CARMEN_PARAM_ONOFF, &dump_enabled, 1,
      carmen_velodyne_dump_handler},
    {module, dump_dirname_var, CARMEN_PARAM_DIR, &dump_dirname, 1,
      carmen_velodyne_dump_handler},
    {module, points_publish_var, CARMEN_PARAM_ONOFF, &points_publish, 1,
      carmen_velodyne_points_handler},
  };

  num_params = sizeof(params)/sizeof(carmen_param_t);
  carmen_param_install_params(argc, argv, params, num_params);

  if (!realpath(calib_filename, calib_path)) {
    calib_path[0] = '\0';
    carmen_warn("\nWarning: Calibration filename %s is invalid\n",
      calib_filename);
  }

  if (!realpath(dump_dirname, dump_path)) {
    dump_path[0] = '\0';
    carmen_warn("\nWarning: Dump directory %s is invalid\n", dump_dirname);
  }

  return num_params;
}
Exemple #22
0
void
read_parameters(SerialDevice *dev, int argc, char **argv)
{
  char* device;

  carmen_param_t gps_dev[] = {
    {"gps", "nmea_dev",  CARMEN_PARAM_STRING, &device, 0, NULL},
    {"gps", "nmea_baud", CARMEN_PARAM_INT,    &(dev->baud),    0, NULL}};
  
  carmen_param_install_params(argc, argv, gps_dev, 
			      sizeof(gps_dev) / sizeof(gps_dev[0]));
  
  strncpy( dev->ttyport, device, MAX_NAME_LENGTH );

  free(device);

}
Exemple #23
0
void
vascocore_get_params( int argc, char **argv, carmen_vascocore_param_p param )
{
  char *laser_type;

  carmen_param_t param_list[] = {
    {"vasco", "laser_type", CARMEN_PARAM_STRING,
     &laser_type, 0, NULL}
  };

  //dbug: add simple history length params

  carmen_param_install_params(argc, argv, param_list,
			      sizeof(param_list) / sizeof(param_list[0]));

  vascocore_get_default_params(param, laser_type);
}
static int 
read_parameters(int argc, char **argv)
{
	int num_items;

	carmen_param_t param_list[] =
	{
			{(char*)"sensor_board_1",  (char*)"x", CARMEN_PARAM_DOUBLE, &(sensor_board_1_pose.position.x),	0, NULL},
			{(char*)"sensor_board_1",  (char*)"y", CARMEN_PARAM_DOUBLE, &(sensor_board_1_pose.position.y),	0, NULL},
			{(char*)"sensor_board_1",  (char*)"z", CARMEN_PARAM_DOUBLE, &(sensor_board_1_pose.position.z),	0, NULL},
			{(char*)"sensor_board_1",  (char*)"roll", CARMEN_PARAM_DOUBLE, &(sensor_board_1_pose.orientation.roll),0, NULL},
			{(char*)"sensor_board_1",  (char*)"pitch", CARMEN_PARAM_DOUBLE, &(sensor_board_1_pose.orientation.pitch),0, NULL},
			{(char*)"sensor_board_1",  (char*)"yaw", CARMEN_PARAM_DOUBLE, &(sensor_board_1_pose.orientation.yaw),	0, NULL},


			{(char*) "velodyne", (char*) "x", CARMEN_PARAM_DOUBLE, &(velodyne_pose.position.x), 0, NULL},
			{(char*) "velodyne", (char*) "y", CARMEN_PARAM_DOUBLE, &(velodyne_pose.position.y), 0, NULL},
			{(char*) "velodyne", (char*) "z", CARMEN_PARAM_DOUBLE, &(velodyne_pose.position.z), 0, NULL},
			{(char*) "velodyne", (char*) "roll", CARMEN_PARAM_DOUBLE, &(velodyne_pose.orientation.roll), 0, NULL},
			{(char*) "velodyne", (char*) "pitch", CARMEN_PARAM_DOUBLE, &(velodyne_pose.orientation.pitch), 0, NULL},
			{(char*) "velodyne", (char*) "yaw", CARMEN_PARAM_DOUBLE, &(velodyne_pose.orientation.yaw), 0, NULL},

			{(char *)"robot", (char*)"length", CARMEN_PARAM_DOUBLE, &car_config.length, 0, NULL},
			{(char *)"robot", (char*)"width", CARMEN_PARAM_DOUBLE, &car_config.width, 0, NULL},
			{(char *)"robot", (char*)"distance_between_rear_car_and_rear_wheels",	CARMEN_PARAM_DOUBLE, &car_config.distance_between_rear_car_and_rear_wheels, 1, NULL},
			{(char *)"robot",  (char*)"distance_between_front_and_rear_axles",		CARMEN_PARAM_DOUBLE, &car_config.distance_between_front_and_rear_axles, 1, NULL},
			{(char *)"robot", (char*)"wheel_radius", CARMEN_PARAM_DOUBLE, &robot_wheel_radius, 0, NULL},

			{(char*)"moving_objects",  (char*)"safe_range_above_sensors", CARMEN_PARAM_DOUBLE, &safe_range_above_sensors, 0, NULL},
			{(char*)"localize_ackerman",  (char*)"number_of_sensors", CARMEN_PARAM_INT, &number_of_sensors, 0, NULL},

	};

	num_items = sizeof(param_list)/sizeof(param_list[0]);
	carmen_param_install_params(argc, argv, param_list, num_items);

	sensor_board_1_to_car_matrix = create_rotation_matrix(sensor_board_1_pose.orientation);

	get_alive_sensors(argc, argv);

	get_sensors_param(argc, argv);


	return 0;
}
Exemple #25
0
int read_parameters(int argc, char **argv)
{
		int num_items;

		carmen_param_t param_list[] = {
				{(char*)"velodyne", (char*)"x", CARMEN_PARAM_DOUBLE, &(velodyne_pose.position.x), 0, NULL},
				{(char*)"velodyne", (char*)"y", CARMEN_PARAM_DOUBLE, &(velodyne_pose.position.y), 0, NULL},
				{(char*)"velodyne", (char*)"z", CARMEN_PARAM_DOUBLE, &(velodyne_pose.position.z), 0, NULL},
				{(char*)"velodyne", (char*)"roll", CARMEN_PARAM_DOUBLE, &(velodyne_pose.orientation.roll), 0, NULL},
				{(char*)"velodyne", (char*)"pitch", CARMEN_PARAM_DOUBLE, &(velodyne_pose.orientation.pitch), 0, NULL},
				{(char*)"velodyne", (char*)"yaw", CARMEN_PARAM_DOUBLE, &(velodyne_pose.orientation.yaw), 0, NULL}
		};

		num_items = sizeof(param_list)/sizeof(param_list[0]);
		carmen_param_install_params(argc, argv, param_list, num_items);

		return 0;
}
Exemple #26
0
void read_parameters(int argc, char **argv)
{
  int num_items;

  carmen_param_t param_list[] = {
    {"robot", "max_t_vel", CARMEN_PARAM_DOUBLE, &max_tv, 1, NULL},
    {"robot", "max_r_vel", CARMEN_PARAM_DOUBLE, &max_rv, 1, NULL},
    {"joystick", "deadspot", CARMEN_PARAM_ONOFF,
     &deadzone, 1, NULL},
    {"joystick", "deadspot_size", CARMEN_PARAM_DOUBLE,
     &deadzone_size, 1, NULL}};

  num_items = sizeof(param_list)/sizeof(param_list[0]);
  carmen_param_install_params(argc, argv, param_list, num_items);

  // Set joystick deadspot
  carmen_set_deadspot(&joystick, deadzone, deadzone_size);
}
Exemple #27
0
void get_logger_params(int argc, char** argv) {

  int num_items;

  carmen_param_t param_list[] = {
    {"logger", "odometry", CARMEN_PARAM_ONOFF, &log_odometry, 0, NULL},
    {"logger", "laser", CARMEN_PARAM_ONOFF, &log_laser, 0, NULL},
    {"logger", "robot_laser", CARMEN_PARAM_ONOFF, &log_robot_laser, 0, NULL},
    {"logger", "localize", CARMEN_PARAM_ONOFF, &log_localize, 0, NULL},
    {"logger", "params", CARMEN_PARAM_ONOFF, &log_params, 0, NULL},
    {"logger", "simulator", CARMEN_PARAM_ONOFF, &log_simulator, 0, NULL},
    {"logger", "gps", CARMEN_PARAM_ONOFF, &log_gps, 0, NULL},
    {"logger", "smart", CARMEN_PARAM_ONOFF, &log_smart, 0, NULL},
    {"logger", "gyro", CARMEN_PARAM_ONOFF, &log_gyro, 0, NULL},
  };

  num_items = sizeof(param_list)/sizeof(param_list[0]);
  carmen_param_install_params(argc, argv, param_list, num_items);
}
static void
read_parameters(int argc, char **argv, carmen_robot_ackerman_config_t *car_config)
{
	carmen_param_t param_list[] = {
			{"robot",	"length",								  		CARMEN_PARAM_DOUBLE, &car_config->length,								 			1, NULL},
			{"robot",	"width",								  		CARMEN_PARAM_DOUBLE, &car_config->width,								 			1, NULL},
			{"robot", 	"distance_between_rear_wheels",		  			CARMEN_PARAM_DOUBLE, &car_config->distance_between_rear_wheels,			 		1, NULL},
			{"robot", 	"distance_between_front_and_rear_axles", 		CARMEN_PARAM_DOUBLE, &car_config->distance_between_front_and_rear_axles, 			1, NULL},
			{"robot", 	"distance_between_front_car_and_front_wheels",	CARMEN_PARAM_DOUBLE, &car_config->distance_between_front_car_and_front_wheels,	1, NULL},
			{"robot", 	"distance_between_rear_car_and_rear_wheels",	CARMEN_PARAM_DOUBLE, &car_config->distance_between_rear_car_and_rear_wheels,		1, NULL},
			{"robot", 	"max_velocity",						  			CARMEN_PARAM_DOUBLE, &car_config->max_v,								 		1, NULL},
			{"robot", 	"max_steering_angle",					  		CARMEN_PARAM_DOUBLE, &car_config->max_phi,								 		1, NULL},
			{"robot", 	"maximum_acceleration_forward",					CARMEN_PARAM_DOUBLE, &car_config->maximum_acceleration_forward,					1, NULL},
			{"robot", 	"maximum_acceleration_reverse",					CARMEN_PARAM_DOUBLE, &car_config->maximum_acceleration_reverse,					1, NULL},
			{"robot", 	"maximum_deceleration_forward",					CARMEN_PARAM_DOUBLE, &car_config->maximum_deceleration_forward,					1, NULL},
			{"robot", 	"maximum_deceleration_reverse",					CARMEN_PARAM_DOUBLE, &car_config->maximum_deceleration_reverse,					1, NULL},
			{"robot", 	"understeer_coeficient",						CARMEN_PARAM_DOUBLE, &car_config->understeer_coeficient,							1, NULL},
	};
	carmen_param_install_params(argc, argv, param_list, sizeof(param_list) / sizeof(param_list[0]));
}
Exemple #29
0
static int read_parameters(int argc, char **argv)
{
  int num_items;
  char *joint_types_string;

  carmen_param_t param_list[] = {
    { "arm", "dev", CARMEN_PARAM_STRING, &(arm_model.dev), 0, NULL},
    { "arm", "num_joints", CARMEN_PARAM_INT, &(arm_model.num_joints), 0, NULL },
    { "arm", "joint_types", CARMEN_PARAM_STRING, &joint_types_string, 0, NULL }
  };
  
  num_items = sizeof(param_list)/sizeof(param_list[0]);
  carmen_param_install_params(argc, argv, param_list, num_items);

  if (arm_model.num_joints > 0) {
    arm_model.joints = (carmen_arm_joint_t *) calloc(arm_model.num_joints, sizeof(int));  // size_t ??
    carmen_parse_arm_joint_types(joint_types_string, arm_model.joints, arm_model.num_joints);
    initialize_arm_message(&arm_state);
  }

  return 0;
}
Exemple #30
0
void get_logger_params(int argc, char** argv) {

  int num_items;

  carmen_param_t param_list[] = {
    {"logger", "odometry",    CARMEN_PARAM_ONOFF, &log_odometry, 0, NULL},
    {"logger", "arm",         CARMEN_PARAM_ONOFF, &log_arm, 0, NULL},
    {"logger", "laser",       CARMEN_PARAM_ONOFF, &log_laser, 0, NULL},
    {"logger", "robot_laser", CARMEN_PARAM_ONOFF, &log_robot_laser, 0, NULL},
    {"logger", "localize",    CARMEN_PARAM_ONOFF, &log_localize, 0, NULL},
    {"logger", "params",      CARMEN_PARAM_ONOFF, &log_params, 0, NULL},
    {"logger", "simulator",   CARMEN_PARAM_ONOFF, &log_simulator, 0, NULL},
    {"logger", "sonar",       CARMEN_PARAM_ONOFF, &log_sonars, 0, NULL},
    {"logger", "bumper",      CARMEN_PARAM_ONOFF, &log_bumpers, 0, NULL},
    {"logger", "gps",         CARMEN_PARAM_ONOFF, &log_gps, 0, NULL},
    {"logger", "imu",         CARMEN_PARAM_ONOFF, &log_imu, 0, NULL},
    {"logger", "motioncmds",  CARMEN_PARAM_ONOFF, &log_motioncmds, 0, NULL}
  };

  num_items = sizeof(param_list)/sizeof(param_list[0]);
  carmen_param_install_params(argc, argv, param_list, num_items);
}