@@ -68,31 +68,31 @@ class PhantomROS {
6868 ros::param::param (std::string (" ~omni_name" ), omni_name, std::string (" phantom" ));
6969 ros::param::param (std::string (" ~reference_frame" ), ref_frame, std::string (" /map" ));
7070 ros::param::param (std::string (" ~units" ), units, std::string (" mm" ));
71-
71+
7272 // Publish button state on NAME/button
7373 std::ostringstream stream1;
7474 stream1 << omni_name << " /button" ;
7575 std::string button_topic = std::string (stream1.str ());
7676 button_publisher = n.advertise <omni_msgs::OmniButtonEvent>(button_topic.c_str (), 100 );
77-
77+
7878 // Publish on NAME/state
7979 std::ostringstream stream2;
8080 stream2 << omni_name << " /state" ;
8181 std::string state_topic_name = std::string (stream2.str ());
8282 state_publisher = n.advertise <omni_msgs::OmniState>(state_topic_name.c_str (), 1 );
83-
83+
8484 // Subscribe to NAME/force_feedback
8585 std::ostringstream stream3;
8686 stream3 << omni_name << " /force_feedback" ;
8787 std::string force_feedback_topic = std::string (stream3.str ());
8888 haptic_sub = n.subscribe (force_feedback_topic.c_str (), 1 , &PhantomROS::force_callback, this );
89-
89+
9090 // Publish on NAME/pose
9191 std::ostringstream stream4;
9292 stream4 << omni_name << " /pose" ;
9393 std::string pose_topic_name = std::string (stream4.str ());
9494 pose_publisher = n.advertise <geometry_msgs::PoseStamped>(pose_topic_name.c_str (), 1 );
95-
95+
9696 // Publish on NAME/joint_states
9797 std::ostringstream stream5;
9898 stream5 << omni_name << " /joint_states" ;
@@ -173,7 +173,7 @@ class PhantomROS {
173173 // TODO: Append Current to the state msg
174174 state_msg.header .stamp = ros::Time::now ();
175175 state_publisher.publish (state_msg);
176-
176+
177177 // Publish the JointState msg
178178 sensor_msgs::JointState joint_state;
179179 joint_state.header .stamp = ros::Time::now ();
@@ -192,7 +192,7 @@ class PhantomROS {
192192 joint_state.name [5 ] = " roll" ;
193193 joint_state.position [5 ] = -state->thetas [6 ] - M_PI;
194194 joint_publisher.publish (joint_state);
195-
195+
196196 // Build the pose msg
197197 geometry_msgs::PoseStamped pose_msg;
198198 pose_msg.header = state_msg.header ;
@@ -204,7 +204,7 @@ class PhantomROS {
204204 pose_publisher.publish (pose_msg);
205205
206206 if ((state->buttons [0 ] != state->buttons_prev [0 ])
207- or (state->buttons [1 ] != state->buttons_prev [1 ]))
207+ or (state->buttons [1 ] != state->buttons_prev [1 ]))
208208 {
209209 if (state->buttons [0 ] == 1 ) {
210210 state->close_gripper = !(state->close_gripper );
@@ -222,7 +222,7 @@ class PhantomROS {
222222 }
223223};
224224
225- HDCallbackCode HDCALLBACK omni_state_callback (void *pUserData)
225+ HDCallbackCode HDCALLBACK omni_state_callback (void *pUserData)
226226{
227227 OmniState *omni_state = static_cast <OmniState *>(pUserData);
228228 if (hdCheckCalibration () == HD_CALIBRATION_NEEDS_UPDATE) {
@@ -265,7 +265,7 @@ HDCallbackCode HDCALLBACK omni_state_callback(void *pUserData)
265265 omni_state->out_vel3 = omni_state->out_vel2 ;
266266 omni_state->out_vel2 = omni_state->out_vel1 ;
267267 omni_state->out_vel1 = omni_state->velocity ;
268-
268+
269269 // ~ // Set forces if locked
270270 // ~ if (omni_state->lock == true) {
271271 // ~ omni_state->force = 0.04 * omni_state->units_ratio * (omni_state->lock_pos - omni_state->position)
@@ -334,7 +334,7 @@ void HHD_Auto_Calibration() {
334334 }
335335 while (hdCheckCalibration () != HD_CALIBRATION_OK) {
336336 usleep (1e6 );
337- if (hdCheckCalibration () == HD_CALIBRATION_NEEDS_MANUAL_INPUT)
337+ if (hdCheckCalibration () == HD_CALIBRATION_NEEDS_MANUAL_INPUT)
338338 ROS_INFO (" Please place the device into the inkwell for calibration" );
339339 else if (hdCheckCalibration () == HD_CALIBRATION_NEEDS_UPDATE) {
340340 ROS_INFO (" Calibration updated successfully" );
0 commit comments