Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Syncing indigo-devel and hydro-devel branches. #61

Merged
merged 4 commits into from
Apr 9, 2015
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -21,3 +21,7 @@
motoman_driver/MotoPlus/_ErrorLog.txt
motoman_driver/MotoPlus/MpRosAllControllers.sdf
motoman_driver/MotoPlus/MpRosAllControllers.v11.suo
*.log
motoman_driver/MotoRos - Github driver folder/$tf/8/bef118b8-349a-45c0-8d86-1ae9c03b511e.gz
motoman_driver/MotoRos - Github driver folder/$tf/localversion.tfb
*.log
4 changes: 4 additions & 0 deletions motoman_driver/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,10 @@
Changelog for package motoman_driver
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

1.2.5 (2015-03-10)
------------------
* Fixed issue with re-connecting to the State Server after closing multiple concurrent connections.

1.2.4 (2014-08-22)
------------------
* Changed message ID for following two message types:
Expand Down
2 changes: 1 addition & 1 deletion motoman_driver/MotoPlus/Controller.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
#ifndef CONTROLLER_H
#define CONTROLLER_H

#define APPLICATION_VERSION "1.2.4"
#define APPLICATION_VERSION "1.2.5"

#define TCP_PORT_MOTION 50240
#define TCP_PORT_STATE 50241
Expand Down
37 changes: 20 additions & 17 deletions motoman_driver/MotoPlus/StateServer.c
Original file line number Diff line number Diff line change
Expand Up @@ -98,19 +98,21 @@ void Ros_StateServer_StartNewConnection(Controller* controller, int sd)
//-----------------------------------------------------------------------
void Ros_StateServer_SendState(Controller* controller)
{
BOOL bHasConnections;
int groupNo;
SimpleMsg sendMsg;
SimpleMsg sendMsgFEx;
int msgSize, fexMsgSize;
BOOL bOkToSendExFeedback;

bHasConnections = TRUE;
BOOL bHasConnections;
BOOL bSuccesfulSend;

printf("Starting State Server Send State task\r\n");
printf("Controller number of group = %d\r\n", controller->numGroup);

while(bHasConnections)
bHasConnections = FALSE;

//Thread for state server should never terminate
while(TRUE)
{
Ros_SimpleMsg_JointFeedbackEx_Init(controller->numGroup, &sendMsgFEx);
bOkToSendExFeedback = TRUE;
Expand All @@ -122,8 +124,12 @@ void Ros_StateServer_SendState(Controller* controller)
fexMsgSize = Ros_SimpleMsg_JointFeedbackEx_Build(groupNo, &sendMsg, &sendMsgFEx);
if(msgSize > 0)
{
if (bHasConnections)
bHasConnections = Ros_StateServer_SendMsgToAllClient(controller, &sendMsg, msgSize);
bSuccesfulSend = Ros_StateServer_SendMsgToAllClient(controller, &sendMsg, msgSize);
if (bSuccesfulSend != bHasConnections)
{
bHasConnections = bSuccesfulSend;
Ros_Controller_SetIOState(IO_FEEDBACK_STATESERVERCONNECTED, bHasConnections);
}
}
else
{
Expand All @@ -135,17 +141,14 @@ void Ros_StateServer_SendState(Controller* controller)
if (controller->numGroup < 2) //only send the ROS_MSG_MOTO_JOINT_FEEDBACK_EX message if we have multiple control groups
bOkToSendExFeedback = FALSE;

if (bHasConnections && bOkToSendExFeedback) //send extended-feedback message
bHasConnections = Ros_StateServer_SendMsgToAllClient(controller, &sendMsgFEx, fexMsgSize);
if (bOkToSendExFeedback) //send extended-feedback message
Ros_StateServer_SendMsgToAllClient(controller, &sendMsgFEx, fexMsgSize);

// Send controller/robot status
if(bHasConnections)
msgSize = Ros_Controller_StatusToMsg(controller, &sendMsg);
if(msgSize > 0)
{
msgSize = Ros_Controller_StatusToMsg(controller, &sendMsg);
if(msgSize > 0)
{
bHasConnections = Ros_StateServer_SendMsgToAllClient(controller, &sendMsg, msgSize);
}
Ros_StateServer_SendMsgToAllClient(controller, &sendMsg, msgSize);
}
mpTaskDelay(STATE_UPDATE_MIN_PERIOD);
}
Expand All @@ -166,7 +169,7 @@ BOOL Ros_StateServer_SendMsgToAllClient(Controller* controller, SimpleMsg* sendM
{
int index;
int ret;
BOOL bHasConnections = FALSE;
BOOL bSuccessfulSend = FALSE;

// Check all active connections
for(index = 0; index < MAX_STATE_CONNECTIONS; index++)
Expand All @@ -182,9 +185,9 @@ BOOL Ros_StateServer_SendMsgToAllClient(Controller* controller, SimpleMsg* sendM
}
else
{
bHasConnections = TRUE;
bSuccessfulSend = TRUE;
}
}
}
return bHasConnections;
return bSuccessfulSend;
}
Binary file modified motoman_driver/MotoPlus/output/DX100/MotoRosDX100/MotoRosDX100.out
Binary file not shown.
Binary file modified motoman_driver/MotoPlus/output/DX200/MotoRosDX200/MotoRosDX200.out
Binary file not shown.
Binary file modified motoman_driver/MotoPlus/output/FS100/MotoRosFS100/MotoRosFS100.out
Binary file not shown.
32 changes: 16 additions & 16 deletions motoman_sia10f_support/urdf/sia10f.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -7,15 +7,15 @@
<link name="base_link">
<visual>
<geometry>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/visual/MOTOMAN_BASE.stl"/>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/visual/motoman_base.stl"/>
</geometry>
<material name="blue">
<color rgba="0 0 1 1"/>
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/collision/MOTOMAN_BASE.stl"/>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/collision/motoman_base.stl"/>
</geometry>
<material name="yellow">
<color rgba="0 1 1 1"/>
Expand All @@ -25,15 +25,15 @@
<link name="link_s">
<visual>
<geometry>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/visual/MOTOMAN_AXIS_S.stl"/>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/visual/motoman_axis_s.stl"/>
</geometry>
<material name="silver">
<color rgba="0.8 0.8 0.8 1"/>
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/collision/MOTOMAN_AXIS_S.stl"/>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/collision/motoman_axis_s.stl"/>
</geometry>
<material name="yellow"/>
</collision>
Expand All @@ -42,14 +42,14 @@
<visual>
<origin rpy="1.57 3.1416 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/visual/MOTOMAN_AXIS_L.stl"/>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/visual/motoman_axis_l.stl"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<origin rpy="1.57 3.1416 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/collision/MOTOMAN_AXIS_L.stl"/>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/collision/motoman_axis_l.stl"/>
</geometry>
<material name="yellow"/>
</collision>
Expand All @@ -58,14 +58,14 @@
<visual>
<origin rpy="0 0 3.1415" xyz="0 0 0"/>
<geometry>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/visual/MOTOMAN_AXIS_E.stl"/>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/visual/motoman_axis_e.stl"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 0 3.1415" xyz="0 0 0"/>
<geometry>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/collision/MOTOMAN_AXIS_E.stl"/>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/collision/motoman_axis_e.stl"/>
</geometry>
<material name="yellow"/>
</collision>
Expand All @@ -74,14 +74,14 @@
<visual>
<origin rpy="1.57 -3.1415 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/visual/MOTOMAN_AXIS_U.stl"/>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/visual/motoman_axis_u.stl"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<origin rpy="1.57 -3.1415 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/collision/MOTOMAN_AXIS_U.stl"/>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/collision/motoman_axis_u.stl"/>
</geometry>
<material name="yellow"/>
</collision>
Expand All @@ -90,14 +90,14 @@
<visual>
<origin rpy="0 0 3.1416" xyz="0 0 0"/>
<geometry>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/visual/MOTOMAN_AXIS_R.stl"/>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/visual/motoman_axis_r.stl"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 0 3.1416" xyz="0 0 0"/>
<geometry>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/collision/MOTOMAN_AXIS_R.stl"/>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/collision/motoman_axis_r.stl"/>
</geometry>
<material name="yellow"/>
</collision>
Expand All @@ -106,28 +106,28 @@
<visual>
<origin rpy="-1.57 0 3.1416" xyz="0 0 0"/>
<geometry>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/visual/MOTOMAN_AXIS_B.stl"/>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/visual/motoman_axis_b.stl"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<origin rpy="-1.57 0 3.1416" xyz="0 0 0"/>
<geometry>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/collision/MOTOMAN_AXIS_B.stl"/>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/collision/motoman_axis_b.stl"/>
</geometry>
<material name="yellow"/>
</collision>
</link>
<link name="link_t">
<visual>
<geometry>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/visual/MOTOMAN_AXIS_T.stl"/>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/visual/motoman_axis_t.stl"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/collision/MOTOMAN_AXIS_T.stl"/>
<mesh filename="package://motoman_sia10f_support/meshes/sia10f/collision/motoman_axis_t.stl"/>
</geometry>
<material name="yellow"/>
</collision>
Expand Down