28 #include <diagnostic_msgs/DiagnosticStatus.h> 30 #include <geometry_msgs/Twist.h> 31 #include <nav_msgs/Odometry.h> 33 #include <cob_msgs/EmergencyStopState.h> 34 #include <control_msgs/JointTrajectoryControllerState.h> 93 is_initialized_bool_ =
false;
100 theta_rob_rad_ = 0.0;
101 vel_x_rob_last_ = 0.0;
102 vel_y_rob_last_ = 0.0;
103 vel_theta_rob_last_ = 0.0;
105 drive_chain_diagnostic_ = diagnostic_status_lookup_.OK;
112 ROS_INFO(
"Timeout loaded from Parameter-Server is: %fs", timeout_);
116 ROS_WARN(
"No parameter timeout on Parameter-Server. Using default: 1.0s");
119 if ( timeout_ < sample_time_ )
121 ROS_WARN(
"Specified timeout < sample_time. Setting timeout to sample_time = %fs", sample_time_);
128 n.
getParam(
"IniDirectory", sIniDirectory);
129 ROS_INFO(
"IniDirectory loaded from Parameter-Server is: %s", sIniDirectory.c_str());
133 sIniDirectory =
"Platform/IniFiles/";
134 ROS_WARN(
"IniDirectory not found on Parameter-Server, using default value: %s", sIniDirectory.c_str());
137 if (n.
hasParam(
"max_trans_velocity"))
139 n.
getParam(
"max_trans_velocity", max_vel_trans_);
140 ROS_INFO(
"Max translational velocity loaded from Parameter-Server is: %fs", max_vel_trans_);
144 ROS_WARN(
"No parameter max_trans_velocity on Parameter-Server. Using default: 1.1 m/s");
145 max_vel_trans_ = 1.1;
149 n.
getParam(
"max_rot_velocity", max_vel_rot_);
150 ROS_INFO(
"Max rotational velocity loaded from Parameter-Server is: %fs", max_vel_rot_);
154 ROS_WARN(
"No parameter max_rot_velocity on Parameter-Server. Using default: 1.8 rad/s");
159 n.
getParam(
"broadcast_tf", broadcast_tf_);
163 iniFile.
SetFileName(sIniDirectory +
"Platform.ini",
"PltfHardwareCoB3.h");
164 iniFile.
GetKeyInt(
"Config",
"NumberOfMotors", &m_iNumJoints,
true);
172 topic_pub_controller_joint_command_ = n.
advertise<control_msgs::JointTrajectoryControllerState> (
"joint_command", 1);
174 topic_pub_odometry_ = n.
advertise<nav_msgs::Odometry>(
"odometry", 1);
202 if(is_initialized_bool_)
203 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"");
205 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"");
206 stat.
add(
"Initialized", is_initialized_bool_);
212 double vx_cmd_mms, vy_cmd_mms, w_cmd_rads;
215 if(isnan(msg->linear.x) || isnan(msg->linear.y) || isnan(msg->angular.z)) {
217 ROS_FATAL(
"Received NaN-value in Twist message. Stopping the robot.");
220 ROS_DEBUG(
"Forced platform velocity commands to zero");
224 if( (fabs(msg->linear.x) > max_vel_trans_) || (fabs(msg->linear.y) > max_vel_trans_) || (fabs(msg->angular.z) > max_vel_rot_))
226 if(fabs(msg->linear.x) > max_vel_trans_)
229 ", which is bigger than the maximal allowed translational velocity: " << max_vel_trans_ <<
" so stop the robot");
231 if(fabs(msg->linear.y) > max_vel_trans_)
234 ", which is bigger than the maximal allowed translational velocity: " << max_vel_trans_ <<
" so stop the robot");
237 if(fabs(msg->angular.z) > max_vel_rot_)
240 ", which is bigger than the maximal allowed rotational velocity: " << max_vel_rot_ <<
" so stop the robot");
250 vx_cmd_mms = msg->linear.x*1000.0;
251 vy_cmd_mms = msg->linear.y*1000.0;
252 w_cmd_rads = msg->angular.z;
258 if (is_initialized_bool_ && drive_chain_diagnostic_==diagnostic_status_lookup_.OK)
260 ROS_DEBUG(
"received new velocity command [cmdVelX=%3.5f,cmdVelY=%3.5f,cmdVelTh=%3.5f]",
261 msg->linear.x, msg->linear.y, msg->angular.z);
272 ROS_DEBUG(
"Forced platform-velocity cmds to zero");
281 EM_state = msg->emergency_state;
283 if (EM_state == msg->EMFREE)
286 if (is_initialized_bool_)
289 ROS_DEBUG(
"Undercarriage Controller EM-Stop released");
296 ROS_DEBUG(
"Undercarriage Controller stopped due to EM-Stop");
301 ROS_DEBUG(
"Forced platform-velocity cmds to zero");
311 control_msgs::JointTrajectoryControllerState joint_state_cmd;
319 joint_state_cmd.desired.positions.resize(m_iNumJoints);
320 joint_state_cmd.desired.velocities.resize(m_iNumJoints);
322 joint_state_cmd.joint_names.push_back(
"fl_caster_r_wheel_joint");
323 joint_state_cmd.joint_names.push_back(
"fl_caster_rotation_joint");
324 joint_state_cmd.joint_names.push_back(
"bl_caster_r_wheel_joint");
325 joint_state_cmd.joint_names.push_back(
"bl_caster_rotation_joint");
326 joint_state_cmd.joint_names.push_back(
"br_caster_r_wheel_joint");
327 joint_state_cmd.joint_names.push_back(
"br_caster_rotation_joint");
328 joint_state_cmd.joint_names.push_back(
"fr_caster_r_wheel_joint");
329 joint_state_cmd.joint_names.push_back(
"fr_caster_rotation_joint");
330 joint_state_cmd.joint_names.resize(m_iNumJoints);
335 joint_state_cmd.desired.positions[i] = 0.0;
336 joint_state_cmd.desired.velocities[i] = 0.0;
341 drive_chain_diagnostic_ = msg->level;
344 if (is_initialized_bool_)
347 if (drive_chain_diagnostic_ != diagnostic_status_lookup_.OK)
350 ROS_DEBUG(
"drive chain not availlable: halt Controller");
358 ROS_DEBUG(
"Forced platform-velocity cmds to zero");
361 if (drive_chain_diagnostic_ != diagnostic_status_lookup_.WARN)
372 if(drive_chain_diagnostic_ != diagnostic_status_lookup_.WARN)
375 topic_pub_controller_joint_command_.
publish(joint_state_cmd);
383 std::vector<double> drive_joint_ang_rad, drive_joint_vel_rads, drive_joint_effort_NM;
384 std::vector<double> steer_joint_ang_rad, steer_joint_vel_rads, steer_joint_effort_NM;
386 joint_state_odom_stamp_ = msg->header.stamp;
389 num_joints = msg->joint_names.size();
391 drive_joint_ang_rad.assign(m_iNumJoints, 0.0);
392 drive_joint_vel_rads.assign(m_iNumJoints, 0.0);
393 drive_joint_effort_NM.assign(m_iNumJoints, 0.0);
395 steer_joint_ang_rad.assign(m_iNumJoints, 0.0);
396 steer_joint_vel_rads.assign(m_iNumJoints, 0.0);
397 steer_joint_effort_NM.assign(m_iNumJoints, 0.0);
403 for(
int i = 0; i < num_joints; i++)
407 if(msg->joint_names[i] ==
"fl_caster_r_wheel_joint")
409 drive_joint_ang_rad[0] = msg->actual.positions[i];
410 drive_joint_vel_rads[0] = msg->actual.velocities[i];
413 if(msg->joint_names[i] ==
"bl_caster_r_wheel_joint")
415 drive_joint_ang_rad[1] = msg->actual.positions[i];
416 drive_joint_vel_rads[1] = msg->actual.velocities[i];
419 if(msg->joint_names[i] ==
"br_caster_r_wheel_joint")
421 drive_joint_ang_rad[2] = msg->actual.positions[i];
422 drive_joint_vel_rads[2] = msg->actual.velocities[i];
425 if(msg->joint_names[i] ==
"fr_caster_r_wheel_joint")
427 drive_joint_ang_rad[3] = msg->actual.positions[i];
428 drive_joint_vel_rads[3] = msg->actual.velocities[i];
431 if(msg->joint_names[i] ==
"fl_caster_rotation_joint")
433 steer_joint_ang_rad[0] = msg->actual.positions[i];
434 steer_joint_vel_rads[0] = msg->actual.velocities[i];
437 if(msg->joint_names[i] ==
"bl_caster_rotation_joint")
439 steer_joint_ang_rad[1] = msg->actual.positions[i];
440 steer_joint_vel_rads[1] = msg->actual.velocities[i];
443 if(msg->joint_names[i] ==
"br_caster_rotation_joint")
445 steer_joint_ang_rad[2] = msg->actual.positions[i];
446 steer_joint_vel_rads[2] = msg->actual.velocities[i];
449 if(msg->joint_names[i] ==
"fr_caster_rotation_joint")
451 steer_joint_ang_rad[3] = msg->actual.positions[i];
452 steer_joint_vel_rads[3] = msg->actual.velocities[i];
459 drive_joint_ang_rad, steer_joint_ang_rad);
483 int main(
int argc,
char** argv)
486 ros::init(argc, argv,
"undercarriage_ctrl");
497 ROS_INFO(
"Undercarriage control successfully initialized.");
499 ROS_FATAL(
"Undercarriage control initialization failed!");
500 throw std::runtime_error(
"Undercarriage control initialization failed, check ini-Files!");
520 double vx_cmd_ms, vy_cmd_ms, w_cmd_rads, dummy;
521 std::vector<double> drive_jointvel_cmds_rads, steer_jointvel_cmds_rads, steer_jointang_cmds_rad;
522 control_msgs::JointTrajectoryControllerState joint_state_cmd;
547 vx_cmd_ms = vx_cmd_ms/1000.0;
548 vy_cmd_ms = vy_cmd_ms/1000.0;
558 joint_state_cmd.desired.velocities.resize(
m_iNumJoints);
560 joint_state_cmd.joint_names.push_back(
"fl_caster_r_wheel_joint");
561 joint_state_cmd.joint_names.push_back(
"fl_caster_rotation_joint");
562 joint_state_cmd.joint_names.push_back(
"bl_caster_r_wheel_joint");
563 joint_state_cmd.joint_names.push_back(
"bl_caster_rotation_joint");
564 joint_state_cmd.joint_names.push_back(
"br_caster_r_wheel_joint");
565 joint_state_cmd.joint_names.push_back(
"br_caster_rotation_joint");
566 joint_state_cmd.joint_names.push_back(
"fr_caster_r_wheel_joint");
567 joint_state_cmd.joint_names.push_back(
"fr_caster_rotation_joint");
578 if( i == 1 || i == 3 || i == 5 || i == 7)
580 joint_state_cmd.desired.positions[i] = steer_jointang_cmds_rad[j];
581 joint_state_cmd.desired.velocities[i] = steer_jointvel_cmds_rads[j];
587 joint_state_cmd.desired.positions[i] = 0.0;
588 joint_state_cmd.desired.velocities[i] = drive_jointvel_cmds_rads[k];
595 joint_state_cmd.desired.positions[i] = 0.0;
596 joint_state_cmd.desired.velocities[i] = 0.0;
611 double vel_x_rob_ms, vel_y_rob_ms, vel_rob_ms, rot_rob_rads, delta_x_rob_m, delta_y_rob_m, delta_theta_rob_rad;
612 double dummy1, dummy2;
625 vel_x_rob_ms, vel_y_rob_ms, rot_rob_rads, dummy2);
628 vel_x_rob_ms = vel_x_rob_ms/1000.0;
629 vel_y_rob_ms = vel_y_rob_ms/1000.0;
630 delta_x_rob_m = delta_x_rob_m/1000.0;
631 delta_y_rob_m = delta_y_rob_m/1000.0;
633 ROS_DEBUG(
"Odmonetry delta is: x=%f, y=%f, th=%f", delta_x_rob_m, delta_y_rob_m, rot_rob_rads);
649 vel_rob_ms = sqrt(vel_x_rob_ms*vel_x_rob_ms + vel_y_rob_ms*vel_y_rob_ms);
669 geometry_msgs::TransformStamped odom_tf;
672 odom_tf.header.frame_id =
"odom_combined";
673 odom_tf.child_frame_id =
"base_footprint";
675 odom_tf.transform.translation.x =
x_rob_m_;
676 odom_tf.transform.translation.y =
y_rob_m_;
677 odom_tf.transform.translation.z = 0.0;
678 odom_tf.transform.rotation = odom_quat;
685 nav_msgs::Odometry odom_top;
688 odom_top.header.frame_id =
"odom_combined";
689 odom_top.child_frame_id =
"base_footprint";
691 odom_top.pose.pose.position.x =
x_rob_m_;
692 odom_top.pose.pose.position.y =
y_rob_m_;
693 odom_top.pose.pose.position.z = 0.0;
694 odom_top.pose.pose.orientation = odom_quat;
695 for(
int i = 0; i < 6; i++)
696 odom_top.pose.covariance[i*6+i] = 0.1;
699 odom_top.twist.twist.linear.x = vel_x_rob_ms;
700 odom_top.twist.twist.linear.y = vel_y_rob_ms;
701 odom_top.twist.twist.linear.z = 0.0;
702 odom_top.twist.twist.angular.x = 0.0;
703 odom_top.twist.twist.angular.y = 0.0;
704 odom_top.twist.twist.angular.z = rot_rob_rads;
705 for(
int i = 0; i < 6; i++)
706 odom_top.twist.covariance[6*i+i] = 0.1;
void topicCallbackEMStop(const cob_msgs::EmergencyStopState::ConstPtr &msg)
ros::Subscriber topic_sub_joint_controller_states_
std::string sIniDirectory
void setEMStopActive(bool bEMStopActive)
void publish(const boost::shared_ptr< M > &message) const
void summary(unsigned char lvl, const std::string s)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void setHardwareID(const std::string &hwid)
UndercarriageCtrlGeom * ucar_ctrl_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
tf::TransformBroadcaster tf_broadcast_odometry_
void add(const std::string &name, TaskFunction f)
ROSCPP_DECL const std::string & getName()
diagnostic_msgs::DiagnosticStatus diagnostic_status_lookup_
void topicCallbackTwistCmd(const geometry_msgs::Twist::ConstPtr &msg)
ROSCPP_DECL void spin(Spinner &spinner)
void GetNewCtrlStateSteerDriveSetValues(std::vector< double > &vdVelGearDriveRadS, std::vector< double > &vdVelGearSteerRadS, std::vector< double > &vdAngGearSteerRad, double &dVelLongMMS, double &dVelLatMMS, double &dRotRobRadS, double &dRotVelRadS)
ros::Time joint_state_odom_stamp_
void InitUndercarriageCtrl(void)
int GetKeyInt(const char *pSect, const char *pKey, int *pValue, bool bWarnIfNotfound=true)
ros::Subscriber topic_sub_CMD_pltf_twist_
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
double vel_theta_rob_last_
void SetDesiredPltfVelocity(double dCmdVelLongMMS, double dCmdVelLatMMS, double dCmdRotRobRadS, double dCmdRotVelRadS)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_DEBUG_STREAM(args)
int main(int argc, char **argv)
ros::Subscriber topic_sub_drive_diagnostic_
void timerCallbackCtrlStep(const ros::TimerEvent &e)
diagnostic_updater::Updater updater_
int SetFileName(std::string fileName, std::string strIniFileUsedBy="", bool bCreate=false)
ros::Publisher topic_pub_joint_state_cmd_
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
void diag_init(diagnostic_updater::DiagnosticStatusWrapper &stat)
ros::Subscriber topic_sub_EM_stop_state_
int drive_chain_diagnostic_
bool getParam(const std::string &key, std::string &s) const
void topicCallbackDiagnostic(const diagnostic_msgs::DiagnosticStatus::ConstPtr &msg)
ros::Publisher topic_pub_controller_joint_command_
bool is_initialized_bool_
void SetActualWheelValues(std::vector< double > vdVelGearDriveRadS, std::vector< double > vdVelGearSteerRadS, std::vector< double > vdDltAngGearDriveRad, std::vector< double > vdAngGearSteerRad)
void add(const std::string &key, const T &val)
bool hasParam(const std::string &key) const
void GetActualPltfVelocity(double &dDeltaLongMM, double &dDeltaLatMM, double &dDeltaRotRobRad, double &dDeltaRotVelRad, double &dVelLongMMS, double &dVelLatMMS, double &dRotRobRadS, double &dRotVelRadS)
ros::Timer timer_ctrl_step_
ros::Publisher topic_pub_odometry_
void topicCallbackJointControllerStates(const control_msgs::JointTrajectoryControllerState::ConstPtr &msg)